From fc9e86262bd8a23480fe733e4062c45043e3fd51 Mon Sep 17 00:00:00 2001 From: podhrmic Date: Fri, 11 Oct 2013 21:30:05 -0600 Subject: [PATCH] Real Time Paparazzi 0.1 uses ChibiOs 2.6.2 Includes all necessary Paparazzi files. --- conf/Makefile.chibios | 309 ++++++++++ conf/airframes/examples/hexarotor_lia_rt.xml | 220 +++++++ conf/boards/lia_1.1_chibios.makefile | 100 ++++ conf/firmwares/rotorcraft_rt.makefile | 245 ++++++++ conf/messages.xml | 12 +- conf/telemetry/default_chibios.xml | 33 ++ sw/airborne/arch/chibios/led_hw.h | 51 ++ sw/airborne/arch/chibios/mcu_arch.c | 42 ++ sw/airborne/arch/chibios/mcu_arch.h | 39 ++ .../arch/chibios/mcu_periph/adc_arch.c | 93 +++ .../arch/chibios/mcu_periph/adc_arch.h | 79 +++ .../arch/chibios/mcu_periph/gpio_arch.c | 32 ++ .../arch/chibios/mcu_periph/gpio_arch.h | 49 ++ .../arch/chibios/mcu_periph/sys_time_arch.c | 50 ++ .../arch/chibios/mcu_periph/sys_time_arch.h | 54 ++ .../arch/chibios/mcu_periph/uart_arch.c | 144 +++++ .../arch/chibios/mcu_periph/uart_arch.h | 36 ++ .../subsystems/actuators/actuators_pwm_arch.c | 46 ++ .../subsystems/actuators/actuators_pwm_arch.h | 49 ++ .../subsystems/radio_control/ppm_arch.c | 37 ++ .../subsystems/radio_control/ppm_arch.h | 36 ++ sw/airborne/boards/lia/chibios/board.c | 85 +++ sw/airborne/boards/lia/chibios/board.h | 242 ++++++++ sw/airborne/boards/lia/chibios/board.mk | 26 + sw/airborne/boards/lia/chibios/chconf.h | 539 ++++++++++++++++++ sw/airborne/boards/lia/chibios/halconf.h | 318 +++++++++++ sw/airborne/boards/lia/chibios/mcuconf.h | 213 +++++++ .../firmwares/rotorcraft/main_chibios.c | 290 ++++++++++ sw/airborne/firmwares/rotorcraft/telemetry.h | 17 + sw/airborne/mcu_periph/uart_pprzi.c | 81 +++ sw/airborne/subsystems/gps/gps_ubx.c | 2 + sw/airborne/subsystems/gps/gps_ubx.h | 43 +- sw/include/std.h | 4 + sw/tools/dfu/stm32_mem.py | 0 34 files changed, 3614 insertions(+), 2 deletions(-) create mode 100644 conf/Makefile.chibios create mode 100644 conf/airframes/examples/hexarotor_lia_rt.xml create mode 100644 conf/boards/lia_1.1_chibios.makefile create mode 100644 conf/firmwares/rotorcraft_rt.makefile create mode 100644 conf/telemetry/default_chibios.xml create mode 100644 sw/airborne/arch/chibios/led_hw.h create mode 100644 sw/airborne/arch/chibios/mcu_arch.c create mode 100644 sw/airborne/arch/chibios/mcu_arch.h create mode 100644 sw/airborne/arch/chibios/mcu_periph/adc_arch.c create mode 100644 sw/airborne/arch/chibios/mcu_periph/adc_arch.h create mode 100644 sw/airborne/arch/chibios/mcu_periph/gpio_arch.c create mode 100644 sw/airborne/arch/chibios/mcu_periph/gpio_arch.h create mode 100644 sw/airborne/arch/chibios/mcu_periph/sys_time_arch.c create mode 100644 sw/airborne/arch/chibios/mcu_periph/sys_time_arch.h create mode 100644 sw/airborne/arch/chibios/mcu_periph/uart_arch.c create mode 100644 sw/airborne/arch/chibios/mcu_periph/uart_arch.h create mode 100644 sw/airborne/arch/chibios/subsystems/actuators/actuators_pwm_arch.c create mode 100644 sw/airborne/arch/chibios/subsystems/actuators/actuators_pwm_arch.h create mode 100644 sw/airborne/arch/chibios/subsystems/radio_control/ppm_arch.c create mode 100644 sw/airborne/arch/chibios/subsystems/radio_control/ppm_arch.h create mode 100644 sw/airborne/boards/lia/chibios/board.c create mode 100644 sw/airborne/boards/lia/chibios/board.h create mode 100644 sw/airborne/boards/lia/chibios/board.mk create mode 100644 sw/airborne/boards/lia/chibios/chconf.h create mode 100644 sw/airborne/boards/lia/chibios/halconf.h create mode 100644 sw/airborne/boards/lia/chibios/mcuconf.h create mode 100644 sw/airborne/firmwares/rotorcraft/main_chibios.c create mode 100644 sw/airborne/mcu_periph/uart_pprzi.c mode change 100644 => 100755 sw/tools/dfu/stm32_mem.py diff --git a/conf/Makefile.chibios b/conf/Makefile.chibios new file mode 100644 index 00000000000..ef3ab8ca465 --- /dev/null +++ b/conf/Makefile.chibios @@ -0,0 +1,309 @@ +# +# Copyright (C) 2013 AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications +# Utah State University, http://aggieair.usu.edu/ +# +# Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) +# Calvin Coopmans (c.r.coopmans@ieee.org) +# +# credits to ENAC team for initial work on ChibiOs and Paparazzi integration +# +# This file is part of paparazzi. +# +# paparazzi 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 2, or (at your option) +# any later version. +# +# paparazzi 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 paparazzi; see the file COPYING. If not, write to +# the Free Software Foundation, 59 Temple Place - Suite 330, +# Boston, MA 02111-1307, USA. +# + +# +# This is the common Makefile for target using chibios +# +CHIBIOS = $(PAPARAZZI_SRC)/sw/ext/chibios +CHIBIOS_SPECIFIC_DIR = $(PAPARAZZI_SRC)/sw/airborne/boards/$(BOARD)/chibios + +# Launch with "make Q=''" to get full command display +Q=@ + +# +# General rules +# + +$(TARGET).srcsnd = $(notdir $($(TARGET).srcs)) +$(TARGET).objso = $($(TARGET).srcs:%.c=$(OBJDIR)/%.o) +$(TARGET).objs = $($(TARGET).objso:%.S=$(OBJDIR)/%.o) + + +############################################################################## +# Build global options +# NOTE: Can be overridden externally. +# + +# Compiler options here. +ifeq ($(USE_OPT),) + USE_OPT = -std=gnu99 -O2 -ggdb -fomit-frame-pointer -falign-functions \ + -W -Wall +endif + +# C specific options here (added to USE_OPT). +ifeq ($(USE_COPT),) + USE_COPT = +endif + +# C++ specific options here (added to USE_OPT). +ifeq ($(USE_CPPOPT),) + USE_CPPOPT = -fno-rtti +endif + +# Enable this if you want the linker to remove unused code and data +ifeq ($(USE_LINK_GC),) + USE_LINK_GC = yes +endif + +# If enabled, this option allows to compile the application in THUMB mode. +ifeq ($(USE_THUMB),) + USE_THUMB = yes +endif + +# Enable this if you want to see the full log while compiling. +ifeq ($(USE_VERBOSE_COMPILE),) + ifeq ($(Q),@) + USE_VERBOSE_COMPILE = no + else + USE_VERBOSE_COMPILE = yes + endif +endif + +# Enable this if you really want to use the STM FWLib. +ifeq ($(USE_FWLIB),) + USE_FWLIB = no +endif + +# +# Build global options +############################################################################## + + +# +# Architecture or project specific options +############################################################################## + + + +############################################################################## +# Project, sources and paths +# +# Imported source files and paths +include $(CHIBIOS_SPECIFIC_DIR)/board.mk +include $(CHIBIOS)/os/hal/platforms/$(CHIBIOS_BOARD_PLATFORM) +include $(CHIBIOS)/os/hal/hal.mk +include $(CHIBIOS)/os/ports/GCC/$(CHIBIOS_BOARD_PORT) +include $(CHIBIOS)/os/kernel/kernel.mk +#include $(CHIBIOS)/test/test.mk + + +# Define linker script file here +LDSCRIPT= $(PORTLD)/$(CHIBIOS_BOARD_LINKER) +# Define linker script file here +#LDSCRIPT= $($(TARGET).LDSCRIPT) + +# C sources that can be compiled in ARM or THUMB mode depending on the global +# setting. +CSRC = $(PORTSRC) \ + $(KERNSRC) \ + $(TESTSRC) \ + $(HALSRC) \ + $(PLATFORMSRC) \ + $(BOARDSRC) \ + $(CHIBIOS)/os/various/evtimer.c \ + $(CHIBIOS)/os/various/syscalls.c \ + $(CHIBIOS_BOARD_MAIN) \ + $($(TARGET).srcs) + +# C++ sources that can be compiled in ARM or THUMB mode depending on the global +# setting. +CPPSRC = + +# C sources to be compiled in ARM mode regardless of the global setting. +# NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler +# option that results in lower performance and larger code size. +ACSRC = + +# C++ sources to be compiled in ARM mode regardless of the global setting. +# NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler +# option that results in lower performance and larger code size. +ACPPSRC = + +# C sources to be compiled in THUMB mode regardless of the global setting. +# NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler +# option that results in lower performance and larger code size. +TCSRC = + +# C sources to be compiled in THUMB mode regardless of the global setting. +# NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler +# option that results in lower performance and larger code size. +TCPPSRC = + +# List ASM source files here +ASMSRC = $(PORTASM) + +INCDIR = $(PORTINC) $(KERNINC) $(TESTINC) \ + $(HALINC) $(PLATFORMINC) $(BOARDINC) \ + $(CHIBIOS)/os/various $(CHIBIOS_SPECIFIC_DIR) + +BUILDDIR := $(OBJDIR) + +# +# Project, sources and paths +############################################################################## + +############################################################################## +# Compiler settings +# +MCU ?= cortex-m3 + +TRGT = arm-none-eabi- +CC = $(TRGT)gcc +CPPC = $(TRGT)g++ +# Enable loading with g++ only if you need C++ runtime support. +# NOTE: You can use C++ even without C++ support if you are careful. C++ +# runtime support makes code size explode. +LD = $(TRGT)gcc +#LD = $(TRGT)g++ +CP = $(TRGT)objcopy +AS = $(TRGT)gcc -x assembler-with-cpp +OD = $(TRGT)objdump +HEX = $(CP) -O ihex +BIN = $(CP) -O binary + +# ARM-specific options here +AOPT = + +# THUMB-specific options here +TOPT = -mthumb -DTHUMB + +# Define C warning options here +CWARN = -Wall -Wextra -Wstrict-prototypes + +# Define C++ warning options here +CPPWARN = -Wall -Wextra + + +# +# Compiler settings +############################################################################## + +############################################################################## +# Start of default section +# + +# List all default C defines here, like -D_DEBUG=1 +DDEFS = + +# List all default ASM defines here, like -D_DEBUG=1 +DADEFS = + +# List all default directories to look for include files here +DINCDIR = + +# List the default directory to look for the libraries here +DLIBDIR = + +# List all default libraries here +DLIBS = -lm +# -lm needed to tell the compiler to use + +# +# End of default section +############################################################################## + +############################################################################## +# Start of user section (extra libraries etc.) +# + +# List all user C define here, like -D_DEBUG=1 +#UDEFS = +UDEFS = $($(TARGET).CFLAGS) + +# Define ASM defines here +UADEFS = + +# List all user directories here +#UINCDIR = +UINCDIR = $(patsubst -I%,%,$(INCLUDES)) + +# List the user directory to look for the libraries here +ULIBDIR = + +# List all user libraries here +ULIBS = + +# +# End of user defines +############################################################################## + +# TODO: remove these... +# Info messages +#$(info CHIBIOS = $(CHIBIOS)) +#$(info PORTSRC = $(PORTSRC)) +#$(info KERNSRC = $(KERNSRC)) +#$(info TESTSRC = $(TESTSRC)) +#$(info HALSRC = $(HALSRC)) +#$(info PLATFORMSRC = $(PLATFORMSRC)) +#$(info BOARDSRC = $(BOARDSRC)) +$(info INCDIR = $(INCDIR)) +$(info UINCDIR = $(UINCDIR)) +$(info CSRC = $(CSRC)) +$(info UDEFS = $(UDEFS)) + +# +# Include upload rules +############################################################################## +# Default upload using black magic probe +#ifndef FLASH_MODE +#FLASH_MODE = JTAG +#endif + +# for now, no luftboot +ASSUMING_LUFTBOOT = "yes" + +# Settings for GDB +# default port configuration for BMP +BMP_PORT = /dev/ttyACM0 +GDB = $(shell which arm-none-eabi-gdb) + + +# Settings for OOCD +$(TARGET).OOCD_INTERFACE=flossjtag +OOCD_INTERFACE=flossjtag +OOCD = $(shell which openocd) + +ifndef $(TARGET).OOCD_BOARD +OOCD_BOARD = lisa-m +else +OOCD_BOARD = $($(TARGET).OOCD_BOARD) +endif +############################################################################### +# Upload makefile +include $(PAPARAZZI_HOME)/conf/Makefile.stm32-upload + + +############################################################################### +ifeq ($(USE_FPU),yes) + USE_OPT += -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant + DDEFS += -DCORTEX_USE_FPU=TRUE +else + DDEFS += -DCORTEX_USE_FPU=FALSE +endif + +# Compile +include $(CHIBIOS)/os/ports/GCC/ARMCMx/rules.mk diff --git a/conf/airframes/examples/hexarotor_lia_rt.xml b/conf/airframes/examples/hexarotor_lia_rt.xml new file mode 100644 index 00000000000..838007367f9 --- /dev/null +++ b/conf/airframes/examples/hexarotor_lia_rt.xml @@ -0,0 +1,220 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + + + + + + + + +
+ + + + + + + + + +
+ + + + + + + + + + + + + + + +
+ +
+ + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + +
+ + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + + + + + + + + + +
+ +
+ + + + + + +
+ +
+ + + + + +
+ +
+ + + +
+ +
+ + + + +
+ +
diff --git a/conf/boards/lia_1.1_chibios.makefile b/conf/boards/lia_1.1_chibios.makefile new file mode 100644 index 00000000000..acea2b860c9 --- /dev/null +++ b/conf/boards/lia_1.1_chibios.makefile @@ -0,0 +1,100 @@ +# +# Copyright (C) 2013 AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications +# Utah State University, http://aggieair.usu.edu/ +# +# Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) +# Calvin Coopmans (c.r.coopmans@ieee.org) +# +# credits to ENAC team for initial work on ChibiOs and Paparazzi integration +# +# This file is part of paparazzi. +# +# paparazzi 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 2, or (at your option) +# any later version. +# +# paparazzi 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 paparazzi; see the file COPYING. If not, write to +# the Free Software Foundation, 59 Temple Place - Suite 330, +# Boston, MA 02111-1307, USA. +# + +# Board definition +BOARD=lia +BOARD_VERSION=1.1_chibios +BOARD_CFG=\"boards/$(BOARD)/chibios/board.h\"#actual chibios defines +# Arch definition +ARCH=chibios# for backwards compatibility with the paparazzi make process +ARCH_DIR=chibios +SRC_ARCH=arch/$(ARCH_DIR) +$(TARGET).ARCHDIR = $(ARCH) + +# since it s Cortex M3 +HARD_FLOAT=no + +# +# default LED configuration +# +BARO_LED ?= 5 +RADIO_CONTROL_LED ?= 4 +GPS_LED ?= 3 +AHRS_ALIGNER_LED ?= 2 +SYS_TIME_LED ?= 1 + +# +# default uart configuration +# +MODEM_PORT ?= UART2 +MODEM_BAUD ?= B57600 + +GPS_PORT ?= UART5 +GPS_BAUD ?= B38400 + + +# default flash mode is via usb dfu bootloader +# possibilities: DFU, SWD, JTAG +FLASH_MODE ?= DFU +STLINK ?= n +DFU_UTIL ?= n + +ifndef NO_LUFTBOOT +$(TARGET).CFLAGS+=-DLUFTBOOT +$(TARGET).LDFLAGS+=-Wl,-Ttext=0x8002000 +endif + +############################################################################## +# Architecture or project specific options +# +# Define project name here (target) +PROJECT = ap + +# Project specific files and paths (see Makefile.chibios for details) +CHIBIOS_BOARD_PLATFORM = STM32F1xx/platform_f105_f107.mk +CHIBIOS_BOARD_PORT = ARMCMx/STM32F1xx/port.mk +CHIBIOS_BOARD_LINKER = STM32F107xC.ld + +############################################################################## +# Compiler settings +# +MCU = cortex-m3 + +# ----------------------------------------------------------------------- +# include Makefile.chibios instead of Makefile.stm32 +$(TARGET).MAKEFILE = chibios + + +# +# default actuator configuration +# +# you can use different actuators by adding a configure option to your firmware section +# e.g. +# +ACTUATORS ?= actuators_pwm diff --git a/conf/firmwares/rotorcraft_rt.makefile b/conf/firmwares/rotorcraft_rt.makefile new file mode 100644 index 00000000000..31e598e5059 --- /dev/null +++ b/conf/firmwares/rotorcraft_rt.makefile @@ -0,0 +1,245 @@ +# Hey Emacs, this is a -*- makefile -*- +# +# Copyright (C) 2010 The Paparazzi Team +# +# modified by AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications +# Utah State University, http://aggieair.usu.edu/ +# +# Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) +# Calvin Coopmans (c.r.coopmans@ieee.org) +# 2013 +# +# This file is part of Paparazzi. +# +# Paparazzi 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 2, or (at your option) +# any later version. +# +# Paparazzi 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 Paparazzi; see the file COPYING. If not, write to +# the Free Software Foundation, 59 Temple Place - Suite 330, +# Boston, MA 02111-1307, USA. +# +# + +CFG_SHARED=$(PAPARAZZI_SRC)/conf/firmwares/subsystems/shared +CFG_ROTORCRAFT_RT=$(PAPARAZZI_SRC)/conf/firmwares/subsystems/rotorcraft + + +SRC_BOARD=boards/$(BOARD) +SRC_FIRMWARE=firmwares/rotorcraft +SRC_SUBSYSTEMS=subsystems + +SRC_ARCH=arch/$(ARCH) + +ROTORCRAFT_INC = -I$(SRC_FIRMWARE) -I$(SRC_BOARD) + + +ap.ARCHDIR = $(ARCH) + +# would be better to auto-generate this +$(TARGET).CFLAGS += -DFIRMWARE=ROTORCRAFT#we are using normal rotorcraft firmware, just different arch +$(TARGET).CFLAGS += -DRTOS#hack for distinquisthing between RT and normal paparazzi config + +#Hack for paparazzi sw/include/std.h +$(TARGET).CFLAGS += -DUSE_CHIBIOS_RTOS + +ap.CFLAGS += $(ROTORCRAFT_INC) +ap.CFLAGS += -DBOARD_CONFIG=$(BOARD_CFG) -DPERIPHERALS_AUTO_INIT +# +# Main (Using RTOS) +# +ap.srcs = $(SRC_FIRMWARE)/main_chibios.c +ap.srcs += mcu.c +ap.srcs += $(SRC_ARCH)/mcu_arch.c + +# +# Math functions +# +ap.srcs += math/pprz_geodetic_int.c math/pprz_geodetic_float.c math/pprz_geodetic_double.c math/pprz_trig_int.c math/pprz_orientation_conversion.c + +ifeq ($(ARCH), stm32) +ap.srcs += lisa/plug_sys.c +endif +# +# Interrupts +# +ifeq ($(ARCH), lpc21) +ap.srcs += $(SRC_ARCH)/armVIC.c +endif + +ifeq ($(ARCH), stm32) +ap.srcs += $(SRC_ARCH)/mcu_periph/gpio_arch.c +endif + +# +# LEDs +# +ap.CFLAGS += -DUSE_LED +ifeq ($(ARCH), stm32) +ap.srcs += $(SRC_ARCH)/led_hw.c +endif + +ifeq ($(BOARD)$(BOARD_TYPE), ardroneraw) +ap.srcs += $(SRC_BOARD)/gpio_ardrone.c +endif + +# frequency of main periodic +PERIODIC_FREQUENCY ?= 512 +ap.CFLAGS += -DPERIODIC_FREQUENCY=$(PERIODIC_FREQUENCY) + +# +# Systime +# +ap.CFLAGS += -DUSE_SYS_TIME +ap.srcs += mcu_periph/sys_time.c $(SRC_ARCH)/mcu_periph/sys_time_arch.c +ifneq ($(SYS_TIME_LED),none) +ap.CFLAGS += -DSYS_TIME_LED=$(SYS_TIME_LED) +endif + +# +# Telemetry/Datalink +# +# include subsystems/rotorcraft/telemetry_transparent.makefile +# or +# include subsystems/rotorcraft/telemetry_xbee_api.makefile +# +ap.srcs += subsystems/settings.c#includes all generated settings +#ap.srcs += $(SRC_ARCH)/subsystems/settings_arch.c -> not necessary + +#ap.srcs += mcu_periph/uart.c -> two file problem, see: http://www.cplusplus.com/forum/general/35718/ +ap.srcs += mcu_periph/uart_pprzi.c +ap.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c +ifeq ($(ARCH), omap) +ap.srcs += $(SRC_ARCH)/serial_port.c +endif + +# I2C is needed for speed controllers and barometers on lisa +##ifeq ($(TARGET), ap) +##$(TARGET).srcs += mcu_periph/i2c.c +##$(TARGET).srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c +##endif + +ap.srcs += subsystems/commands.c +ap.srcs += subsystems/actuators.c + +# +# Radio control choice +# +# include subsystems/rotorcraft/radio_control_ppm.makefile +# or +# include subsystems/rotorcraft/radio_control_spektrum.makefile +# + +# +# Actuator choice +# +# include subsystems/rotorcraft/actuators_mkk.makefile +# or +# include subsystems/rotorcraft/actuators_asctec.makefile +# or +# include subsystems/rotorcraft/actuators_asctec_v2.makefile +# + +# +# IMU choice +# +# include subsystems/rotorcraft/imu_b2v1.makefile +# or +# include subsystems/rotorcraft/imu_b2v1_1.makefile +# or +# include subsystems/rotorcraft/imu_crista.makefile +# + +# +# AIR DATA and BARO (if needed) +# +ap.srcs += subsystems/air_data.c + +include $(CFG_SHARED)/baro_board.makefile + +# +# Analog Backend +# +#TODO +ap.CFLAGS += -DUSE_ADC +ap.srcs += $(SRC_ARCH)/mcu_periph/adc_arch.c +ap.srcs += subsystems/electrical.c +##ifeq ($(ARCH), stm32) +##ap.srcs += $(SRC_ARCH)/mcu_periph/adc_arch.c +##ap.srcs += subsystems/electrical.c +##endif +#ifeq ($(ARCH), lpc21) +#ap.CFLAGS += -DUSE_ADC +#ap.srcs += $(SRC_ARCH)/mcu_periph/adc_arch.c +#ap.srcs += subsystems/electrical.c +# baro has variable offset amplifier on booz board +#ifeq ($(BOARD), booz) +#ap.CFLAGS += -DUSE_DAC +#ap.srcs += $(SRC_ARCH)/mcu_periph/dac_arch.c +#endif +#else ifeq ($(ARCH), stm32) +#ap.CFLAGS += -DUSE_ADC +#ap.srcs += $(SRC_ARCH)/mcu_periph/adc_arch.c +#ap.srcs += subsystems/electrical.c +#else ifeq ($(BOARD)$(BOARD_TYPE), ardronesdk) +#ap.srcs += $(SRC_BOARD)/electrical_dummy.c +#else ifeq ($(BOARD)$(BOARD_TYPE), ardroneraw) +#ap.srcs += $(SRC_BOARD)/electrical_raw.c +#endif + + + +# +# GPS choice +# +# include subsystems/rotorcraft/gps_ubx.makefile +# or +# include subsystems/rotorcraft/gps_skytraq.makefile +# or +# nothing +# + + +# +# AHRS choice +# +# include subsystems/rotorcraft/ahrs_cmpl.makefile +# or +# include subsystems/rotorcraft/ahrs_lkf.makefile +# + +ap.srcs += $(SRC_FIRMWARE)/autopilot.c + +ap.srcs += state.c + +ap.srcs += $(SRC_FIRMWARE)/stabilization.c +ap.srcs += $(SRC_FIRMWARE)/stabilization/stabilization_none.c +ap.srcs += $(SRC_FIRMWARE)/stabilization/stabilization_rate.c + +ap.CFLAGS += -DUSE_NAVIGATION +ap.srcs += $(SRC_FIRMWARE)/guidance/guidance_h.c +ap.srcs += $(SRC_FIRMWARE)/guidance/guidance_h_ref.c +ap.srcs += $(SRC_FIRMWARE)/guidance/guidance_v.c +ap.srcs += $(SRC_FIRMWARE)/guidance/guidance_v_ref.c +ap.srcs += $(SRC_FIRMWARE)/guidance/guidance_v_adapt.c + +# +# INS choice +# +# include subsystems/rotorcraft/ins.makefile +# or +# include subsystems/rotorcraft/ins_extended.makefile +# +# extra: +# include subsystems/rotorcraft/ins_hff.makefile +# + +ap.srcs += $(SRC_FIRMWARE)/navigation.c +ap.srcs += subsystems/navigation/common_flight_plan.c diff --git a/conf/messages.xml b/conf/messages.xml index 3b09735149c..3001e288211 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -653,7 +653,17 @@ - + + + + + + + + + + + diff --git a/conf/telemetry/default_chibios.xml b/conf/telemetry/default_chibios.xml new file mode 100644 index 00000000000..4e91339e07e --- /dev/null +++ b/conf/telemetry/default_chibios.xml @@ -0,0 +1,33 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sw/airborne/arch/chibios/led_hw.h b/sw/airborne/arch/chibios/led_hw.h new file mode 100644 index 00000000000..7a9f2c20018 --- /dev/null +++ b/sw/airborne/arch/chibios/led_hw.h @@ -0,0 +1,51 @@ +/* + * Copyright (C) 2013 AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + * Utah State University, http://aggieair.usu.edu/ + * + * Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + * Calvin Coopmans (c.r.coopmans@ieee.org) + * + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ +/** + * @brief chibios arch dependant led manipulation macros + */ +#ifndef LED_HW_H +#define LED_HW_H + +/* + * hal.h is needed for palXXX functions + */ +#include "hal.h" + +/* + * Regular GPIO driven LEDs + */ +#define _LED_GPIO(i) i +#define _LED_GPIO_PIN(i) i + +#define LED_GPIO(i) _LED_GPIO(LED_ ## i ## _GPIO) +#define LED_GPIO_PIN(i) _LED_GPIO_PIN(LED_ ## i ## _GPIO_PIN) + +#define LED_ON(i) palClearPad(LED_GPIO(i), LED_GPIO_PIN(i)) +#define LED_OFF(i) palSetPad(LED_GPIO(i), LED_GPIO_PIN(i)) +#define LED_TOGGLE(i) palTogglePad(LED_GPIO(i), LED_GPIO_PIN(i)) +#define LED_PERIODIC() {} + +#endif /* LED_HW_H */ diff --git a/sw/airborne/arch/chibios/mcu_arch.c b/sw/airborne/arch/chibios/mcu_arch.c new file mode 100644 index 00000000000..b937d9cdd4f --- /dev/null +++ b/sw/airborne/arch/chibios/mcu_arch.c @@ -0,0 +1,42 @@ +/* + * Copyright (C) 2013 AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + * Utah State University, http://aggieair.usu.edu/ + * + * Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + * Calvin Coopmans (c.r.coopmans@ieee.org) + * + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ +/** + * @brief chibios arch dependant microcontroller initialisation functions. + * @details Mostly empty defines, because Chibios takes + * care of mcu initialization + */ +#include "mcu.h" +#include "ch.h" + +/* + * SCB_VTOR has to be relocaed if Luftboot is used + */ +void mcu_arch_init(void) { +#if LUFTBOOT +PRINT_CONFIG_MSG("We are running luftboot, the interrupt vector is being relocated.") + SCB_VTOR = 0x00002000; +#endif +} diff --git a/sw/airborne/arch/chibios/mcu_arch.h b/sw/airborne/arch/chibios/mcu_arch.h new file mode 100644 index 00000000000..cd5ad00b131 --- /dev/null +++ b/sw/airborne/arch/chibios/mcu_arch.h @@ -0,0 +1,39 @@ +/* + * Copyright (C) 2013 AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + * Utah State University, http://aggieair.usu.edu/ + * + * Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + * Calvin Coopmans (c.r.coopmans@ieee.org) + * + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ +/** + * @brief chibios arch dependant microcontroller initialisation functions. + * @details Mostly empty defines, because Chibios takes + * care of mcu initialization + */ +#ifndef CHIBIOS_MCU_ARCH_H +#define CHIBIOS_MCU_ARCH_H + +#define mcu_int_enable() {} +#define mcu_int_disable() {} + +extern void mcu_arch_init(void); + +#endif /* CHIBIOS_MCU_ARCH_H */ diff --git a/sw/airborne/arch/chibios/mcu_periph/adc_arch.c b/sw/airborne/arch/chibios/mcu_periph/adc_arch.c new file mode 100644 index 00000000000..13c09c70fdf --- /dev/null +++ b/sw/airborne/arch/chibios/mcu_periph/adc_arch.c @@ -0,0 +1,93 @@ +/* + * Copyright (C) 2013 AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + * Utah State University, http://aggieair.usu.edu/ + * + * Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + * Calvin Coopmans (c.r.coopmans@ieee.org) + * + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ +/** + * @brief chibios arch dependant adc drivers + * @note Empty for now, just to provide compatibilty + * Comments below from stm32/mcu_periph/adc_arch.c + * + */ + +/* + For better understanding of timer and GPIO settings: + + Table of GPIO pins available per ADC: + + ADC1/2: ADC3: + C0 -> PA0 C0 -> PA0 + C1 -> PA1 C1 -> PA1 + C2 -> PA2 C2 -> PA2 + C3 -> PA3 C3 -> PA3 + C4 -> PA4 C4 -> PF6 + C5 -> PA5 C5 -> PF7 + C6 -> PA6 C6 -> PF8 + C7 -> PA7 C7 -> PF9 + C8 -> PB0 C8 -> PF10 + C9 -> PB1 + C10 -> PC0 C10 -> PC0 + C11 -> PC1 C11 -> PC1 + C12 -> PC2 C12 -> PC2 + C13 -> PC3 C13 -> PC3 + C14 -> PC4 + C15 -> PC5 + + Table of timers available per ADC (from libstm/src/stm32_adc.c): + + T1_TRGO: Timer1 TRGO event (ADC1, ADC2 and ADC3) + T1_CC4: Timer1 capture compare4 (ADC1, ADC2 and ADC3) + T2_TRGO: Timer2 TRGO event (ADC1 and ADC2) + T2_CC1: Timer2 capture compare1 (ADC1 and ADC2) + T3_CC4: Timer3 capture compare4 (ADC1 and ADC2) + T4_TRGO: Timer4 TRGO event (ADC1 and ADC2) + TIM8_CC4: External interrupt line 15 or Timer8 capture compare4 event (ADC1 and ADC2) + T4_CC3: Timer4 capture compare3 (ADC3 only) + T8_CC2: Timer8 capture compare2 (ADC3 only) + T8_CC4: Timer8 capture compare4 (ADC3 only) + T5_TRGO: Timer5 TRGO event (ADC3 only) + T5_CC4: Timer5 capture compare4 (ADC3 only) + + By setting ADC_ExternalTrigInjecConv_None, injected conversion + is started by software instead of external trigger for any ADC. + + Table of APB per Timer (from libstm/src/stm32_tim.c): + + RCC_APB1: TIM2, TIM3, TIM4, TIM5, TIM7 (non-advanced timers) + RCC_APB2: TIM1, TIM8 (advanced timers) + +*/ +#include "mcu_periph/adc.h" + +void adc_buf_channel(uint8_t adc_channel, + struct adc_buf * s, + uint8_t av_nb_sample){ + //TODO + (void) adc_channel; + (void) s; + (void) av_nb_sample; +} + +void adc_init( void ) { + //TODO +} diff --git a/sw/airborne/arch/chibios/mcu_periph/adc_arch.h b/sw/airborne/arch/chibios/mcu_periph/adc_arch.h new file mode 100644 index 00000000000..70f3e1ab06b --- /dev/null +++ b/sw/airborne/arch/chibios/mcu_periph/adc_arch.h @@ -0,0 +1,79 @@ +/* + * Copyright (C) 2013 AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + * Utah State University, http://aggieair.usu.edu/ + * + * Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + * Calvin Coopmans (c.r.coopmans@ieee.org) + * + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ +/** + * @brief chibios arch dependant adc drivers + * @note Empty for now, just to provide compatibilty + * Comments below from stm32/mcu_periph/adc_arch.c + * + */ +#ifndef ADC_ARCH_H +#define ADC_ARCH_H + +#include BOARD_CONFIG + +// NB_ADCx_CHANNELS +enum adc1_channels { +#ifdef USE_AD1_1 + ADC1_C1, +#endif +#ifdef USE_AD1_2 + ADC1_C2, +#endif +#ifdef USE_AD1_3 + ADC1_C3, +#endif +#ifdef USE_AD1_4 + ADC1_C4, +#endif + NB_ADC1_CHANNELS +}; + +enum adc2_channels { +#ifdef USE_AD2_1 + ADC2_C1, +#endif +#ifdef USE_AD2_2 + ADC2_C2, +#endif +#ifdef USE_AD2_3 + ADC2_C3, +#endif +#ifdef USE_AD2_4 + ADC2_C4, +#endif + NB_ADC2_CHANNELS +}; + +#ifdef NB_ADC +#undef NB_ADC +#endif + +#define NB_ADC (NB_ADC1_CHANNELS + NB_ADC2_CHANNELS) + +#define AdcBank0(x) (x) +#define AdcBank1(x) (x+NB_ADC) + +#endif /* ADC_ARCH_H */ diff --git a/sw/airborne/arch/chibios/mcu_periph/gpio_arch.c b/sw/airborne/arch/chibios/mcu_periph/gpio_arch.c new file mode 100644 index 00000000000..6233d0a8373 --- /dev/null +++ b/sw/airborne/arch/chibios/mcu_periph/gpio_arch.c @@ -0,0 +1,32 @@ +/* + * Copyright (C) 2013 AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + * Utah State University, http://aggieair.usu.edu/ + * + * Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + * Calvin Coopmans (c.r.coopmans@ieee.org) + * + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ +/** + * @brief chibios arch dependant gpio functions + * @details In Chibios palSet/Clear/Toggle(port, pin) + * replaces gpio functions + * + */ +#include "mcu_periph/gpio.h" diff --git a/sw/airborne/arch/chibios/mcu_periph/gpio_arch.h b/sw/airborne/arch/chibios/mcu_periph/gpio_arch.h new file mode 100644 index 00000000000..6733caf33b1 --- /dev/null +++ b/sw/airborne/arch/chibios/mcu_periph/gpio_arch.h @@ -0,0 +1,49 @@ +/* + * Copyright (C) 2013 AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + * Utah State University, http://aggieair.usu.edu/ + * + * Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + * Calvin Coopmans (c.r.coopmans@ieee.org) + * + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ +/** + * @brief chibios arch dependant gpio functions + * @details In Chibios palSet/Clear/Toggle(port, pin) + * replaces gpio functions + * + */ +#ifndef GPIO_ARCH_H +#define GPIO_ARCH_H + +/** + * Set a gpio output to high level. + */ +static inline void gpio_output_high(uint32_t port, uint16_t pin) { + palSetPad(port, pin); +} + +/** + * Clear a gpio output to low level. + */ +static inline void gpio_output_low(uint32_t port, uint16_t pin) { + palClearPad(port, pin); +} + +#endif /* GPIO_ARCH_H */ diff --git a/sw/airborne/arch/chibios/mcu_periph/sys_time_arch.c b/sw/airborne/arch/chibios/mcu_periph/sys_time_arch.c new file mode 100644 index 00000000000..3016cd57292 --- /dev/null +++ b/sw/airborne/arch/chibios/mcu_periph/sys_time_arch.c @@ -0,0 +1,50 @@ +/* + * Copyright (C) 2013 AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + * Utah State University, http://aggieair.usu.edu/ + * + * Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + * Calvin Coopmans (c.r.coopmans@ieee.org) + * + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ +/** + * @brief chibios arch dependant implementation of sys time functions + * @note Partially implemented (no CPU monitor), some extra variables + * for monitoring number of threads and free memory. + * + */ +#include "mcu_periph/sys_time.h" + +size_t heap_fragments; +size_t heap_free_total; +uint32_t core_free_memory; +uint8_t thread_counter; +uint32_t cpu_counter; +uint32_t idle_counter; +float cpu_frequency; + +void sys_time_arch_init( void ) { + heap_fragments = 0; + heap_free_total = 0; + core_free_memory = 0; + thread_counter = 0; + cpu_counter = 0; + idle_counter = 0; + cpu_frequency = 0.0; +} diff --git a/sw/airborne/arch/chibios/mcu_periph/sys_time_arch.h b/sw/airborne/arch/chibios/mcu_periph/sys_time_arch.h new file mode 100644 index 00000000000..415b8280691 --- /dev/null +++ b/sw/airborne/arch/chibios/mcu_periph/sys_time_arch.h @@ -0,0 +1,54 @@ +/* + * Copyright (C) 2013 AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + * Utah State University, http://aggieair.usu.edu/ + * + * Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + * Calvin Coopmans (c.r.coopmans@ieee.org) + * + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ +/** + * @brief chibios arch dependant implementation of sys time functions + * @note Partially implemented (no CPU monitor), some extra variables + * for monitoring number of threads and free memory. + * + */ +#ifndef SYS_TIME_ARCH_H +#define SYS_TIME_ARCH_H + +#include "mcu_periph/sys_time.h" + +extern size_t heap_fragments; +extern size_t heap_free_total; +extern uint32_t core_free_memory; +extern uint8_t thread_counter; +extern uint32_t cpu_counter; +extern uint32_t idle_counter; +extern float cpu_frequency; + +static inline uint32_t get_sys_time_usec(void) { + //TODO + return 0; +} + +static inline void sys_time_usleep(uint32_t us) { +(void)us; + //TODO +} +#endif /* SYS_TIME_ARCH_H */ diff --git a/sw/airborne/arch/chibios/mcu_periph/uart_arch.c b/sw/airborne/arch/chibios/mcu_periph/uart_arch.c new file mode 100644 index 00000000000..10f9f1c7953 --- /dev/null +++ b/sw/airborne/arch/chibios/mcu_periph/uart_arch.c @@ -0,0 +1,144 @@ +/* + * Copyright (C) 2013 AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + * Utah State University, http://aggieair.usu.edu/ + * + * Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + * Calvin Coopmans (c.r.coopmans@ieee.org) + * + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ +/** + * @brief chibios arch dependant implementation of uart/serial drivers + * @details Partially implemented (no error callbacks yet). Since ChibiOs + * has SerialDriver, it is better to use that one instead of Uart + * drivers, although it makes backward compatibility more difficutl. + * DMA is already implemented. + * @note The peripheral settings should use config (baudrate etc) from + * makefiles, some makro should be used. + */ +#include "mcu_periph/uart.h" +#include "hal.h" + + +#ifdef USE_UART1 +static const SerialConfig usart1_config = +{ +57600, /* BITRATE */ +0, /* USART CR1 */ +USART_CR2_STOP1_BITS | USART_CR2_LINEN, /* USART CR2 */ +0 /* USART CR3 */ +}; +void uart1_init(void) { + sdStart(&SD1, &usart1_config); + uart1.reg_addr = &SD1; +} +#endif + + +#ifdef USE_UART2 +static const SerialConfig usart2_config = +{ +57600, /* BITRATE */ +0, /* USART CR1 */ +USART_CR2_STOP1_BITS | USART_CR2_LINEN, /* USART CR2 */ +0 /* USART CR3 */ +}; +void uart2_init(void) { + sdStart(&SD2, &usart2_config); + uart2.reg_addr = &SD2; +} +#endif + +#ifdef USE_UART3 +static const SerialConfig usart3_config = +{ +57600, /* BITRATE */ +0, /* USART CR1 */ +USART_CR2_STOP1_BITS | USART_CR2_LINEN, /* USART CR2 */ +0 /* USART CR3 */ +}; +void uart3_init(void) { + sdStart(&SD3, &usart3_config); + uart3.reg_addr = &SD3; +} +#endif + +#ifdef USE_UART4 +static const SerialConfig usart4_config = +{ +57600, /* BITRATE */ +0, /* USART CR1 */ +USART_CR2_STOP1_BITS | USART_CR2_LINEN, /* USART CR2 */ +0 /* USART CR3 */ +}; +void uart4_init(void) { + sdStart(&SD4, &usart4_config); + uart4.reg_addr = &SD4; +} +#endif + +#ifdef USE_UART5 +static const SerialConfig usart5_config = +{ +115200, /* BITRATE */ +0, /* USART CR1 */ +USART_CR2_STOP1_BITS | USART_CR2_LINEN, /* USART CR2 */ +0 /* USART CR3 */ +}; +void uart5_init(void) { + sdStart(&SD5, &usart5_config); + uart5.reg_addr = &SD5; +} +#endif + +/* + * Set baudrate (from the serialConfig) + * @note Baudrate is set in sdStart, no need for implementation + */ +void uart_periph_set_baudrate(struct uart_periph* p, uint32_t baud) { + (void*) p; + (void) baud; +} + +/* + * Set mode (not necessary, or can be set by SerialConfig) + */ +void uart_periph_set_mode(struct uart_periph* p, bool_t tx_enabled, bool_t rx_enabled, bool_t hw_flow_control) { + (void*) p; + (void) tx_enabled; + (void) rx_enabled; + (void) hw_flow_control; +} + +/* +* Uart transmit implementation +*/ +void uart_transmit(struct uart_periph* p, uint8_t data ) { + sdWrite((SerialDriver*)p->reg_addr, &data, sizeof(data)); +} + +/* +* Uart transmit buffer implementation +* Typical use: +* uint8_t tx_switch[10] = { 0x01, 0x08, 0x12, 0x34, 0x56, 0x78, 0x12, 0x34, '\r' }; +* uart_transmit_buffer(&uart2, tx_switch, sizeof(tx_switch)); +*/ +void uart_transmit_buffer(struct uart_periph* p, uint8_t* data_buffer, size_t length) { + sdWrite((SerialDriver*)p->reg_addr, data_buffer, length); +} diff --git a/sw/airborne/arch/chibios/mcu_periph/uart_arch.h b/sw/airborne/arch/chibios/mcu_periph/uart_arch.h new file mode 100644 index 00000000000..6358c73e3cc --- /dev/null +++ b/sw/airborne/arch/chibios/mcu_periph/uart_arch.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2013 AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + * Utah State University, http://aggieair.usu.edu/ + * + * Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + * Calvin Coopmans (c.r.coopmans@ieee.org) + * + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ +/** + * @brief chibios arch dependant implementation of uart/serial drivers + * @details Partially implemented (no error callbacks yet). Since ChibiOs + * has SerialDriver, it is better to use that one instead of Uart + * drivers, although it makes backward compatibility more difficutl. + * DMA is already implemented. + */ +#ifndef CHIBIOS_UART_ARCH_H +#define CHIBIOS_UART_ARCH_H + +#endif /* STM32_UART_ARCH_H */ diff --git a/sw/airborne/arch/chibios/subsystems/actuators/actuators_pwm_arch.c b/sw/airborne/arch/chibios/subsystems/actuators/actuators_pwm_arch.c new file mode 100644 index 00000000000..8a6720c3627 --- /dev/null +++ b/sw/airborne/arch/chibios/subsystems/actuators/actuators_pwm_arch.c @@ -0,0 +1,46 @@ +/* + * Copyright (C) 2013 AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + * Utah State University, http://aggieair.usu.edu/ + * + * Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + * Calvin Coopmans (c.r.coopmans@ieee.org) + * + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ +/** + * @brief chibios arch dependant pwm actuator drivers + * @note Empty for now, just to provide compatibilty + * + */ +#include "subsystems/actuators/actuators_pwm_arch.h" +#include "subsystems/actuators/actuators_pwm.h" + +int32_t actuators_pwm_values[ACTUATORS_PWM_NB]; + +/** PWM arch init called by generic pwm driver + */ +void actuators_pwm_arch_init(void) { + //TODO +} + +/** Set pulse widths from actuator values, assumed to be in us + */ +void actuators_pwm_commit(void) { + //TODO +} diff --git a/sw/airborne/arch/chibios/subsystems/actuators/actuators_pwm_arch.h b/sw/airborne/arch/chibios/subsystems/actuators/actuators_pwm_arch.h new file mode 100644 index 00000000000..476493bd5ad --- /dev/null +++ b/sw/airborne/arch/chibios/subsystems/actuators/actuators_pwm_arch.h @@ -0,0 +1,49 @@ +/* + * Copyright (C) 2013 AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + * Utah State University, http://aggieair.usu.edu/ + * + * Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + * Calvin Coopmans (c.r.coopmans@ieee.org) + * + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ +/** + * @brief chibios arch dependant pwm actuator drivers + * @note Empty for now, just to provide compatibilty + * + */ +#ifndef ACTUATORS_PWM_ARCH_H +#define ACTUATORS_PWM_ARCH_H + +#include "std.h" + +#include BOARD_CONFIG + +#ifndef ACTUATORS_PWM_NB +#define ACTUATORS_PWM_NB 8 +#endif + +extern int32_t actuators_pwm_values[ACTUATORS_PWM_NB]; + +extern void actuators_pwm_commit(void); + +#define ActuatorPwmSet(_i, _v) { actuators_pwm_values[_i] = _v; } +#define ActuatorsPwmCommit actuators_pwm_commit + +#endif /* ACTUATORS_PWM_ARCH_H */ diff --git a/sw/airborne/arch/chibios/subsystems/radio_control/ppm_arch.c b/sw/airborne/arch/chibios/subsystems/radio_control/ppm_arch.c new file mode 100644 index 00000000000..94ecc8a98a2 --- /dev/null +++ b/sw/airborne/arch/chibios/subsystems/radio_control/ppm_arch.c @@ -0,0 +1,37 @@ +/* + * Copyright (C) 2013 AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + * Utah State University, http://aggieair.usu.edu/ + * + * Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + * Calvin Coopmans (c.r.coopmans@ieee.org) + * + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ +/** + * @brief chibios arch dependant ppm drivers + * @note Empty for now, just to provide compatibilty + * + */ +#include "subsystems/radio_control.h" +#include "subsystems/radio_control/ppm.h" + +/* + * TODO: implement + */ +void ppm_arch_init ( void ) { } diff --git a/sw/airborne/arch/chibios/subsystems/radio_control/ppm_arch.h b/sw/airborne/arch/chibios/subsystems/radio_control/ppm_arch.h new file mode 100644 index 00000000000..5c869ef069d --- /dev/null +++ b/sw/airborne/arch/chibios/subsystems/radio_control/ppm_arch.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2013 AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + * Utah State University, http://aggieair.usu.edu/ + * + * Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + * Calvin Coopmans (c.r.coopmans@ieee.org) + * + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ +/** + * @brief chibios arch dependant ppm drivers + * @note Empty for now, just to provide compatibilty + * + */ +#ifndef PPM_ARCH_H +#define PPM_ARCH_H + +#define PPM_NB_CHANNEL RADIO_CONTROL_NB_CHANNEL + +#endif /* PPM_ARCH_H */ diff --git a/sw/airborne/boards/lia/chibios/board.c b/sw/airborne/boards/lia/chibios/board.c new file mode 100644 index 00000000000..524aa37293c --- /dev/null +++ b/sw/airborne/boards/lia/chibios/board.c @@ -0,0 +1,85 @@ +/* + ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio + + modified by: AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + Utah State University, http://aggieair.usu.edu/ + + Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + Calvin Coopmans (c.r.coopmans@ieee.org) + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +#include "ch.h" +#include "hal.h" + +/** + * @brief PAL setup. + * @details Digital I/O ports static configuration as defined in @p board.h. + * This variable is used by the HAL when initializing the PAL driver. + */ +#if HAL_USE_PAL || defined(__DOXYGEN__) +const PALConfig pal_default_config = +{ + {VAL_GPIOAODR, VAL_GPIOACRL, VAL_GPIOACRH}, + {VAL_GPIOBODR, VAL_GPIOBCRL, VAL_GPIOBCRH}, + {VAL_GPIOCODR, VAL_GPIOCCRL, VAL_GPIOCCRH}, + {VAL_GPIODODR, VAL_GPIODCRL, VAL_GPIODCRH}, + {VAL_GPIOEODR, VAL_GPIOECRL, VAL_GPIOECRH}, +}; +#endif + +/* + * Early initialization code. + * This initialization must be performed just after stack setup and before + * any other initialization. + */ +void __early_init(void) { + + stm32_clock_init(); +} + +#if HAL_USE_MMC_SPI +/* + * Card detection through the card internal pull-up on D3. + */ +bool_t mmc_lld_is_card_inserted(MMCDriver *mmcp) { + static bool_t last_status = FALSE; +// (void)mmcp; +// if ((palReadLatch(GPIOA) & PAL_PORT_BIT(GPIOA_SPI3_CS_MMC)) == 0) + return last_status; +// return last_status = (bool_t)palReadPad(GPIOA, GPIOA_SPI3_CS_MMC); +} + +/* + * Card write protection detection is not possible, the card is always + * reported as not protected. + */ +bool_t mmc_lld_is_write_protected(MMCDriver *mmcp) { + + (void)mmcp; + return FALSE; +} +#endif + +/* + * Board-specific initialization code. + */ +void boardInit(void) { + + /* + * Several I/O pins are re-mapped: + * JTAG TRST to LED + */ + AFIO->MAPR |= AFIO_MAPR_USART3_REMAP_PARTIALREMAP | AFIO_MAPR_SWJ_CFG_NOJNTRST ; +} diff --git a/sw/airborne/boards/lia/chibios/board.h b/sw/airborne/boards/lia/chibios/board.h new file mode 100644 index 00000000000..8c1c384e840 --- /dev/null +++ b/sw/airborne/boards/lia/chibios/board.h @@ -0,0 +1,242 @@ +/* + ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio + + modified by: AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + Utah State University, http://aggieair.usu.edu/ + + Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + Calvin Coopmans (c.r.coopmans@ieee.org) + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +#ifndef _BOARD_H_ +#define _BOARD_H_ + +/* + * Setup for the Lia board + */ + +/* + * Board identifier. + */ +#define BOARD_LIA_STM32F105RC +#define BOARD_NAME "Lia 1.1 STM32F105RC" + +/* + * Board frequencies. + */ +#define STM32_HSECLK 12000000 + +/* + * MCU type, supported types are defined in ./os/hal/platforms/hal_lld.h. + */ +#define STM32F10X_CL + +/* + * IO pins assignments. + */ + /* +#define GPIOA_LED1 8 +#define GPIOB_LED2 4 +#define GPIOC_LED3 2 +#define GPIOC_LED4 5 +#define GPIOC_LED5 15 +*/ +/* + * I/O ports initial setup, this configuration is established soon after reset + * in the initialization code. + * + * The digits have the following meaning: + * 0 - Analog input. + * 1 - Push Pull output 10MHz. + * 2 - Push Pull output 2MHz. + * 3 - Push Pull output 50MHz. + * 4 - Digital input. + * 5 - Open Drain output 10MHz. + * 6 - Open Drain output 2MHz. + * 7 - Open Drain output 50MHz. + * 8 - Digital input with PullUp or PullDown resistor depending on ODR. + * 9 - Alternate Push Pull output 10MHz. + * A - Alternate Push Pull output 2MHz. + * B - Alternate Push Pull output 50MHz. + * C - Reserved. + * D - Alternate Open Drain output 10MHz. + * E - Alternate Open Drain output 2MHz. + * F - Alternate Open Drain output 50MHz. + * Please refer to the STM32 Reference Manual for details. + */ + +/* + * Port A setup. + * Everything input with pull-up except: + * PA0 - B - Alternate Push Pull output 50MHz (SERVO5). + * PA1 - B - Alternate Push Pull output 50MHz (SERVO6). + * PA2 - B - Alternate Push Pull output 50MHz (UART2_TX). + * PA3 - 4 - Digital input (UART2_RX). + * PA4 - B - Alternate Push Pull output 50MHz (EXTSPI_SS). + * PA5 - B - Alternate Push Pull output 50MHz (EXTSPI_SCK). + * PA6 - 4 - Digital input. (EXTSPI_MISO). + * PA7 - B - Alternate Push Pull output 50MHz (EXTSPI_MOSI). + * PA8 - 7 - Open Drain output 50MHz (LED1). + * PA9 - 4 - Digital input. (USB_VBUS). + * PA10 - 4 - Digital input. (UART1_RX). + * PA11 - 4 - Digital input (USB_DM). + * PA12 - 4 - Digital input (USB_DP). + * PA13 - 4 - Digital input (JTAG_TMS). + * PA14 - 4 - Digital input (JTAG_TCK). + * PA15 - 4 - Digital input (JTAG_TDI). + */ +#define VAL_GPIOACRL 0xB4BB4BBB /* PA7...PA0 */ +#define VAL_GPIOACRH 0x44444447 /* PA15...PA8 */ +#define VAL_GPIOAODR 0xFFFFFFFF + +/* + * Port B setup: + * PB0 - 4 - Digital input (BARO_DRDY). + * PB1 - 4 - Digital input (EXTSPI_DRDY). + * PB2 - 4 - Digital input (IMU_ACC_DRDY). + * PB3 - 4 - Digital input (JTAG_TDO). + * PB4 - 7 - Open Drain output 50MHz (LED2). + * PB5 - 4 - Digital input (IMU_MAG_DRDY). + * PB6 - 7 - Open Drain output 50MHz. (SERVO7/I2C1_SCL). + * PB7 - 7 - Open Drain output 50MHz. (SERVO8/I2C1_SDA). + * PB8 - 4 - Digital input. (CAN_RX). + * PB9 - 7 - Open Drain output 50MHz. (CAN_TX). + * PB10 - 7 - Open Drain output 50MHz. (I2C2_SCL). + * PB11 - 7 - Open Drain output 50MHz. (I2C2_SDA). + * PB12 - B - Alternate Push Pull output 50MHz (IMU_ACC_CS). + * PB13 - B - Alternate Push Pull output 50MHz (IMU_SPI_SCK). + * PB14 - 4 - Digital input (IMU_SPI_MISO). + * PB15 - B - Alternate Push Pull output 50MHz (IMU_SPI_MOSI). + */ +#define VAL_GPIOBCRL 0x77474444 /* PB7...PB0 */ +#define VAL_GPIOBCRH 0xB4BB7774 /* PB15...PB8 */ +#define VAL_GPIOBODR 0xFFFFFFFF + +/* + * Port C setup: + * PC0 - 0 - Analog input (ADC2). + * PC1 - 0 - Analog input (ADC3). + * PC2 - 7 - Open Drain output 50MHz (LED3). + * PC3 - 0 - Analog input (ADC1). + * PC4 - 0 - Analog input (VBAT_MEAS). + * PC5 - 7 - Open Drain output 50MHz (LED4). + * PC6 - B - Alternate Push Pull output 50MHz (SERVO1). + * PC7 - B - Alternate Push Pull output 50MHz (SERVO2). + * PC8 - B - Alternate Push Pull output 50MHz (SERVO3). + * PC9 - B - Alternate Push Pull output 50MHz (SERVO4). + * PC10 - B - Alternate Push Pull output 50MHz (UART3_TX). + * PC11 - 4 - Digital input (UART3_RX). + * PC12 - B - Alternate Push Pull output 50MHz (PC12-UART5_TX). + * PC13 - B - Alternate Push Pull output 50MHz (IMU_GYRO_SS). + * PC14 - 4 - Digital input (IMU_GYRO_DRDY). + * PC15 - 7 - Open Drain output 50MHz (LED5). + */ +#define VAL_GPIOCCRL 0xBB700700 /* PC7...PC0 */ +#define VAL_GPIOCCRH 0x74BB4BBB /* PC15...PC8 */ +#define VAL_GPIOCODR 0xFFFFFFFF + +/* + * Port D setup: + * PD0 - 8 - Digital input with PullUp or PullDown resistor depending on ODR. (OSC_IN). + * PD1 - 8 - Digital input with PullUp or PullDown resistor depending on ODR. (OSC_OUT). + * PD2 - 4 - Digital input (UART5_RX). + * PD3 - 8 - Digital input with PullUp or PullDown resistor depending on ODR. (unconnected). + * PD4 - 8 - Digital input with PullUp or PullDown resistor depending on ODR. (unconnected). + * PD5 - 8 - Digital input with PullUp or PullDown resistor depending on ODR. (unconnected). + * PD6 - 8 - Digital input with PullUp or PullDown resistor depending on ODR. (unconnected). + * PD7 - 8 - Digital input with PullUp or PullDown resistor depending on ODR. (unconnected). + * PD8 - 8 - Digital input with PullUp or PullDown resistor depending on ODR. (unconnected). + * PD9 - 8 - Digital input with PullUp or PullDown resistor depending on ODR. (unconnected). + * PD10 - 8 - Digital input with PullUp or PullDown resistor depending on ODR. (unconnected). + * PD11 - 8 - Digital input with PullUp or PullDown resistor depending on ODR. (unconnected). + * PD12 - 8 - Digital input with PullUp or PullDown resistor depending on ODR. (unconnected). + * PD13 - 8 - Digital input with PullUp or PullDown resistor depending on ODR. (unconnected). + * PD14 - 8 - Digital input with PullUp or PullDown resistor depending on ODR. (unconnected). + * PD15 - 8 - Digital input with PullUp or PullDown resistor depending on ODR. (unconnected). + */ +#define VAL_GPIODCRL 0x88888488 /* PD7...PD0 */ +#define VAL_GPIODCRH 0x88888888 /* PD15...PD8 */ +#define VAL_GPIODODR 0xFFFFFFFF + +/* + * Port E setup. + * Everything input with pull-up ( - 8 - Digital input with PullUp or PullDown resistor depending on ODR. (unconnected).) + */ +#define VAL_GPIOECRL 0x88888888 /* PE7...PE0 */ +#define VAL_GPIOECRH 0x88888888 /* PE15...PE8 */ +#define VAL_GPIOEODR 0xFFFFFFFF + + +/* + * IO pins assignments. (example for leds) + */ +//#define GPIOA_PIN8 8 //LED1 +//#define GPIOB_PIN4 4 //LED2 +//#define GPIOC_PIN2 2 //LED3 +//#define GPIOC_PIN5 5 //LED4 +//#define GPIOC_PIN15 15 //LED5 + + +/* + * Onboard LEDs (paparazzi compatible) + */ + +/* 1red, on PA8 */ +//#ifndef USE_LED_1 +//#define USE_LED_1 1 +//#endif +#define LED_1_GPIO GPIOA +#define LED_1_GPIO_PIN 8 + +/* 2green, shared with JTAG_TRST */ +//#ifndef USE_LED_2 +//#define USE_LED_2 1 +//#endif +#define LED_2_GPIO GPIOB +#define LED_2_GPIO_PIN 4 + +/* 3green, shared with ADC12 (ADC_6 on connector ANALOG2) */ +//#ifndef USE_LED_3 +//#define USE_LED_3 1 +//#endif +#define LED_3_GPIO GPIOC +#define LED_3_GPIO_PIN 2 + +/* 4red, shared with ADC15 (ADC_4 on connector ANALOG2) */ +//#ifndef USE_LED_4 +//#define USE_LED_4 1 +//#endif +#define LED_4_GPIO GPIOC +#define LED_4_GPIO_PIN 5 + +/* 5green, on PC15 */ +//#ifndef USE_LED_5 +//#define USE_LED_5 1 +//#endif +#define LED_5_GPIO GPIOC +#define LED_5_GPIO_PIN 15 + + +#if !defined(_FROM_ASM_) +#ifdef __cplusplus +extern "C" { +#endif + void boardInit(void); +#ifdef __cplusplus +} +#endif +#endif /* _FROM_ASM_ */ + +#endif /* _BOARD_H_ */ diff --git a/sw/airborne/boards/lia/chibios/board.mk b/sw/airborne/boards/lia/chibios/board.mk new file mode 100644 index 00000000000..0ac4ebff8a8 --- /dev/null +++ b/sw/airborne/boards/lia/chibios/board.mk @@ -0,0 +1,26 @@ +# +# ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio +# +# modified by: AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications +# Utah State University, http://aggieair.usu.edu/ +# +# Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) +# Calvin Coopmans (c.r.coopmans@ieee.org) +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# Required include directories +BOARDINC = $(CHIBIOS_SPECIFIC_DIR) + +# List of all the board related files. +BOARDSRC = ${BOARDINC}/board.c diff --git a/sw/airborne/boards/lia/chibios/chconf.h b/sw/airborne/boards/lia/chibios/chconf.h new file mode 100644 index 00000000000..b5a8734bbcf --- /dev/null +++ b/sw/airborne/boards/lia/chibios/chconf.h @@ -0,0 +1,539 @@ +/* + ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio + + modified by: AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + Utah State University, http://aggieair.usu.edu/ + + Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + Calvin Coopmans (c.r.coopmans@ieee.org) + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +/** + * @file templates/chconf.h + * @brief Configuration file template. + * @details A copy of this file must be placed in each project directory, it + * contains the application specific kernel settings. + * + * @addtogroup config + * @details Kernel related settings and hooks. + * @{ + */ + +#ifndef _CHCONF_H_ +#define _CHCONF_H_ + +#include "mcu_periph/sys_time_arch.h" + +/*===========================================================================*/ +/** + * @name Kernel parameters and options + * @{ + */ +/*===========================================================================*/ + +/** + * @brief System tick frequency. + * @details Frequency of the system timer that drives the system ticks. This + * setting also defines the system tick time unit. + */ +#if !defined(CH_FREQUENCY) || defined(__DOXYGEN__) +#define CH_FREQUENCY 10000 +#endif + +/** + * @brief Round robin interval. + * @details This constant is the number of system ticks allowed for the + * threads before preemption occurs. Setting this value to zero + * disables the preemption for threads with equal priority and the + * round robin becomes cooperative. Note that higher priority + * threads can still preempt, the kernel is always preemptive. + * + * @note Disabling the round robin preemption makes the kernel more compact + * and generally faster. + */ +#if !defined(CH_TIME_QUANTUM) || defined(__DOXYGEN__) +#define CH_TIME_QUANTUM 20 +#endif + +/** + * @brief Managed RAM size. + * @details Size of the RAM area to be managed by the OS. If set to zero + * then the whole available RAM is used. The core memory is made + * available to the heap allocator and/or can be used directly through + * the simplified core memory allocator. + * + * @note In order to let the OS manage the whole RAM the linker script must + * provide the @p __heap_base__ and @p __heap_end__ symbols. + * @note Requires @p CH_USE_MEMCORE. + */ +#if !defined(CH_MEMCORE_SIZE) || defined(__DOXYGEN__) +#define CH_MEMCORE_SIZE 0 +#endif + +/** + * @brief Idle thread automatic spawn suppression. + * @details When this option is activated the function @p chSysInit() + * does not spawn the idle thread automatically. The application has + * then the responsibility to do one of the following: + * - Spawn a custom idle thread at priority @p IDLEPRIO. + * - Change the main() thread priority to @p IDLEPRIO then enter + * an endless loop. In this scenario the @p main() thread acts as + * the idle thread. + * . + * @note Unless an idle thread is spawned the @p main() thread must not + * enter a sleep state. + */ +#if !defined(CH_NO_IDLE_THREAD) || defined(__DOXYGEN__) +#define CH_NO_IDLE_THREAD FALSE +#endif + +/** @} */ + +/*===========================================================================*/ +/** + * @name Performance options + * @{ + */ +/*===========================================================================*/ + +/** + * @brief OS optimization. + * @details If enabled then time efficient rather than space efficient code + * is used when two possible implementations exist. + * + * @note This is not related to the compiler optimization options. + * @note The default is @p TRUE. + */ +#if !defined(CH_OPTIMIZE_SPEED) || defined(__DOXYGEN__) +#define CH_OPTIMIZE_SPEED TRUE +#endif + +/** @} */ + +/*===========================================================================*/ +/** + * @name Subsystem options + * @{ + */ +/*===========================================================================*/ + +/** + * @brief Threads registry APIs. + * @details If enabled then the registry APIs are included in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_REGISTRY) || defined(__DOXYGEN__) +#define CH_USE_REGISTRY TRUE +#endif + +/** + * @brief Threads synchronization APIs. + * @details If enabled then the @p chThdWait() function is included in + * the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_WAITEXIT) || defined(__DOXYGEN__) +#define CH_USE_WAITEXIT TRUE +#endif + +/** + * @brief Semaphores APIs. + * @details If enabled then the Semaphores APIs are included in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_SEMAPHORES) || defined(__DOXYGEN__) +#define CH_USE_SEMAPHORES TRUE +#endif + +/** + * @brief Semaphores queuing mode. + * @details If enabled then the threads are enqueued on semaphores by + * priority rather than in FIFO order. + * + * @note The default is @p FALSE. Enable this if you have special requirements. + * @note Requires @p CH_USE_SEMAPHORES. + */ +#if !defined(CH_USE_SEMAPHORES_PRIORITY) || defined(__DOXYGEN__) +#define CH_USE_SEMAPHORES_PRIORITY FALSE +#endif + +/** + * @brief Atomic semaphore API. + * @details If enabled then the semaphores the @p chSemSignalWait() API + * is included in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_SEMAPHORES. + */ +#if !defined(CH_USE_SEMSW) || defined(__DOXYGEN__) +#define CH_USE_SEMSW TRUE +#endif + +/** + * @brief Mutexes APIs. + * @details If enabled then the mutexes APIs are included in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_MUTEXES) || defined(__DOXYGEN__) +#define CH_USE_MUTEXES TRUE +#endif + +/** + * @brief Conditional Variables APIs. + * @details If enabled then the conditional variables APIs are included + * in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_MUTEXES. + */ +#if !defined(CH_USE_CONDVARS) || defined(__DOXYGEN__) +#define CH_USE_CONDVARS TRUE +#endif + +/** + * @brief Conditional Variables APIs with timeout. + * @details If enabled then the conditional variables APIs with timeout + * specification are included in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_CONDVARS. + */ +#if !defined(CH_USE_CONDVARS_TIMEOUT) || defined(__DOXYGEN__) +#define CH_USE_CONDVARS_TIMEOUT TRUE +#endif + +/** + * @brief Events Flags APIs. + * @details If enabled then the event flags APIs are included in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_EVENTS) || defined(__DOXYGEN__) +#define CH_USE_EVENTS TRUE +#endif + +/** + * @brief Events Flags APIs with timeout. + * @details If enabled then the events APIs with timeout specification + * are included in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_EVENTS. + */ +#if !defined(CH_USE_EVENTS_TIMEOUT) || defined(__DOXYGEN__) +#define CH_USE_EVENTS_TIMEOUT TRUE +#endif + +/** + * @brief Synchronous Messages APIs. + * @details If enabled then the synchronous messages APIs are included + * in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_MESSAGES) || defined(__DOXYGEN__) +#define CH_USE_MESSAGES TRUE +#endif + +/** + * @brief Synchronous Messages queuing mode. + * @details If enabled then messages are served by priority rather than in + * FIFO order. + * + * @note The default is @p FALSE. Enable this if you have special requirements. + * @note Requires @p CH_USE_MESSAGES. + */ +#if !defined(CH_USE_MESSAGES_PRIORITY) || defined(__DOXYGEN__) +#define CH_USE_MESSAGES_PRIORITY FALSE +#endif + +/** + * @brief Mailboxes APIs. + * @details If enabled then the asynchronous messages (mailboxes) APIs are + * included in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_SEMAPHORES. + */ +#if !defined(CH_USE_MAILBOXES) || defined(__DOXYGEN__) +#define CH_USE_MAILBOXES TRUE +#endif + +/** + * @brief I/O Queues APIs. + * @details If enabled then the I/O queues APIs are included in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_QUEUES) || defined(__DOXYGEN__) +#define CH_USE_QUEUES TRUE +#endif + +/** + * @brief Core Memory Manager APIs. + * @details If enabled then the core memory manager APIs are included + * in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_MEMCORE) || defined(__DOXYGEN__) +#define CH_USE_MEMCORE TRUE +#endif + +/** + * @brief Heap Allocator APIs. + * @details If enabled then the memory heap allocator APIs are included + * in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_MEMCORE and either @p CH_USE_MUTEXES or + * @p CH_USE_SEMAPHORES. + * @note Mutexes are recommended. + */ +#if !defined(CH_USE_HEAP) || defined(__DOXYGEN__) +#define CH_USE_HEAP TRUE +#endif + +/** + * @brief C-runtime allocator. + * @details If enabled the the heap allocator APIs just wrap the C-runtime + * @p malloc() and @p free() functions. + * + * @note The default is @p FALSE. + * @note Requires @p CH_USE_HEAP. + * @note The C-runtime may or may not require @p CH_USE_MEMCORE, see the + * appropriate documentation. + */ +#if !defined(CH_USE_MALLOC_HEAP) || defined(__DOXYGEN__) +#define CH_USE_MALLOC_HEAP FALSE +#endif + +/** + * @brief Memory Pools Allocator APIs. + * @details If enabled then the memory pools allocator APIs are included + * in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_MEMPOOLS) || defined(__DOXYGEN__) +#define CH_USE_MEMPOOLS TRUE +#endif + +/** + * @brief Dynamic Threads APIs. + * @details If enabled then the dynamic threads creation APIs are included + * in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_WAITEXIT. + * @note Requires @p CH_USE_HEAP and/or @p CH_USE_MEMPOOLS. + */ +#if !defined(CH_USE_DYNAMIC) || defined(__DOXYGEN__) +#define CH_USE_DYNAMIC TRUE +#endif + +/** @} */ + +/*===========================================================================*/ +/** + * @name Debug options + * @{ + */ +/*===========================================================================*/ + +/** + * @brief Debug option, system state check. + * @details If enabled the correct call protocol for system APIs is checked + * at runtime. + * + * @note The default is @p FALSE. + */ +#if !defined(CH_DBG_SYSTEM_STATE_CHECK) || defined(__DOXYGEN__) +#define CH_DBG_SYSTEM_STATE_CHECK FALSE +#endif + +/** + * @brief Debug option, parameters checks. + * @details If enabled then the checks on the API functions input + * parameters are activated. + * + * @note The default is @p FALSE. + */ +#if !defined(CH_DBG_ENABLE_CHECKS) || defined(__DOXYGEN__) +#define CH_DBG_ENABLE_CHECKS FALSE +#endif + +/** + * @brief Debug option, consistency checks. + * @details If enabled then all the assertions in the kernel code are + * activated. This includes consistency checks inside the kernel, + * runtime anomalies and port-defined checks. + * + * @note The default is @p FALSE. + */ +#if !defined(CH_DBG_ENABLE_ASSERTS) || defined(__DOXYGEN__) +#define CH_DBG_ENABLE_ASSERTS FALSE +#endif + +/** + * @brief Debug option, trace buffer. + * @details If enabled then the context switch circular trace buffer is + * activated. + * + * @note The default is @p FALSE. + */ +#if !defined(CH_DBG_ENABLE_TRACE) || defined(__DOXYGEN__) +#define CH_DBG_ENABLE_TRACE FALSE +#endif + +/** + * @brief Debug option, stack checks. + * @details If enabled then a runtime stack check is performed. + * + * @note The default is @p FALSE. + * @note The stack check is performed in a architecture/port dependent way. + * It may not be implemented or some ports. + * @note The default failure mode is to halt the system with the global + * @p panic_msg variable set to @p NULL. + */ +#if !defined(CH_DBG_ENABLE_STACK_CHECK) || defined(__DOXYGEN__) +#define CH_DBG_ENABLE_STACK_CHECK FALSE +#endif + +/** + * @brief Debug option, stacks initialization. + * @details If enabled then the threads working area is filled with a byte + * value when a thread is created. This can be useful for the + * runtime measurement of the used stack. + * + * @note The default is @p FALSE. + */ +#if !defined(CH_DBG_FILL_THREADS) || defined(__DOXYGEN__) +#define CH_DBG_FILL_THREADS FALSE +#endif + +/** + * @brief Debug option, threads profiling. + * @details If enabled then a field is added to the @p Thread structure that + * counts the system ticks occurred while executing the thread. + * + * @note The default is @p TRUE. + * @note This debug option is defaulted to TRUE because it is required by + * some test cases into the test suite. + */ +#if !defined(CH_DBG_THREADS_PROFILING) || defined(__DOXYGEN__) +#define CH_DBG_THREADS_PROFILING TRUE +#endif + +/** @} */ + +/*===========================================================================*/ +/** + * @name Kernel hooks + * @{ + */ +/*===========================================================================*/ + +/** + * @brief Threads descriptor structure extension. + * @details User fields added to the end of the @p Thread structure. + */ +#if !defined(THREAD_EXT_FIELDS) || defined(__DOXYGEN__) +#define THREAD_EXT_FIELDS \ + /* Add threads custom fields here.*/ +#endif + +/** + * @brief Threads initialization hook. + * @details User initialization code added to the @p chThdInit() API. + * + * @note It is invoked from within @p chThdInit() and implicitly from all + * the threads creation APIs. + */ +#if !defined(THREAD_EXT_INIT_HOOK) || defined(__DOXYGEN__) +#define THREAD_EXT_INIT_HOOK(tp) { \ + /* Add threads initialization code here.*/ \ +} +#endif + +/** + * @brief Threads finalization hook. + * @details User finalization code added to the @p chThdExit() API. + * + * @note It is inserted into lock zone. + * @note It is also invoked when the threads simply return in order to + * terminate. + */ +#if !defined(THREAD_EXT_EXIT_HOOK) || defined(__DOXYGEN__) +#define THREAD_EXT_EXIT_HOOK(tp) { \ + /* Add threads finalization code here.*/ \ +} +#endif + +/** + * @brief Context switch hook. + * @details This hook is invoked just before switching between threads. + */ +#if !defined(THREAD_CONTEXT_SWITCH_HOOK) || defined(__DOXYGEN__) +#define THREAD_CONTEXT_SWITCH_HOOK(ntp, otp) { \ + /* System halt code here.*/ \ +} +#endif + +/** + * @brief Idle Loop hook. + * @details This hook is continuously invoked by the idle thread loop. + */ +#if !defined(IDLE_LOOP_HOOK) || defined(__DOXYGEN__) +#define IDLE_LOOP_HOOK() { \ + /* Idle loop code here.*/ \ +} +#endif + +/** + * @brief System tick event hook. + * @details This hook is invoked in the system tick handler immediately + * after processing the virtual timers queue. + */ +#if !defined(SYSTEM_TICK_EVENT_HOOK) || defined(__DOXYGEN__) +#define SYSTEM_TICK_EVENT_HOOK() { \ + \ +} +#endif + +/** + * @brief System halt hook. + * @details This hook is invoked in case to a system halting error before + * the system is halted. + */ +#if !defined(SYSTEM_HALT_HOOK) || defined(__DOXYGEN__) +#define SYSTEM_HALT_HOOK() { \ + /* System halt code here.*/ \ +} +#endif + +/** @} */ + +/*===========================================================================*/ +/* Port-specific settings (override port settings defaulted in chcore.h). */ +/*===========================================================================*/ + +#endif /* _CHCONF_H_ */ + +/** @} */ diff --git a/sw/airborne/boards/lia/chibios/halconf.h b/sw/airborne/boards/lia/chibios/halconf.h new file mode 100644 index 00000000000..9a7aab89cea --- /dev/null +++ b/sw/airborne/boards/lia/chibios/halconf.h @@ -0,0 +1,318 @@ +/* + ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio + + modified by: AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + Utah State University, http://aggieair.usu.edu/ + + Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + Calvin Coopmans (c.r.coopmans@ieee.org) + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +/** + * @file templates/halconf.h + * @brief HAL configuration header. + * @details HAL configuration file, this file allows to enable or disable the + * various device drivers from your application. You may also use + * this file in order to override the device drivers default settings. + * + * @addtogroup HAL_CONF + * @{ + */ + +#ifndef _HALCONF_H_ +#define _HALCONF_H_ + +#include "mcuconf.h" + +/** + * @brief Enables the TM subsystem. + */ +#if !defined(HAL_USE_TM) || defined(__DOXYGEN__) +#define HAL_USE_TM FALSE +#endif + +/** + * @brief Enables the PAL subsystem. + */ +#if !defined(HAL_USE_PAL) || defined(__DOXYGEN__) +#define HAL_USE_PAL TRUE +#endif + +/** + * @brief Enables the ADC subsystem. + */ +#if !defined(HAL_USE_ADC) || defined(__DOXYGEN__) +#define HAL_USE_ADC FALSE +#endif + +/** + * @brief Enables the CAN subsystem. + */ +#if !defined(HAL_USE_CAN) || defined(__DOXYGEN__) +#define HAL_USE_CAN FALSE +#endif + +/** + * @brief Enables the EXT subsystem. + */ +#if !defined(HAL_USE_EXT) || defined(__DOXYGEN__) +#define HAL_USE_EXT FALSE +#endif + +/** + * @brief Enables the GPT subsystem. + */ +#if !defined(HAL_USE_GPT) || defined(__DOXYGEN__) +#define HAL_USE_GPT FALSE +#endif + +/** + * @brief Enables the I2C subsystem. + */ +#if !defined(HAL_USE_I2C) || defined(__DOXYGEN__) +#define HAL_USE_I2C FALSE +#endif + +/** + * @brief Enables the ICU subsystem. + */ +#if !defined(HAL_USE_ICU) || defined(__DOXYGEN__) +#define HAL_USE_ICU FALSE +#endif + +/** + * @brief Enables the MAC subsystem. + */ +#if !defined(HAL_USE_MAC) || defined(__DOXYGEN__) +#define HAL_USE_MAC FALSE +#endif + +/** + * @brief Enables the MMC_SPI subsystem. + */ +#if !defined(HAL_USE_MMC_SPI) || defined(__DOXYGEN__) +#define HAL_USE_MMC_SPI FALSE +#endif + +/** + * @brief Enables the PWM subsystem. + */ +#if !defined(HAL_USE_PWM) || defined(__DOXYGEN__) +#define HAL_USE_PWM FALSE +#endif + +/** + * @brief Enables the RTC subsystem. + */ +#if !defined(HAL_USE_RTC) || defined(__DOXYGEN__) +#define HAL_USE_RTC FALSE +#endif + +/** + * @brief Enables the SDC subsystem. + */ +#if !defined(HAL_USE_SDC) || defined(__DOXYGEN__) +#define HAL_USE_SDC FALSE +#endif + +/** + * @brief Enables the SERIAL subsystem. + */ +#if !defined(HAL_USE_SERIAL) || defined(__DOXYGEN__) +#define HAL_USE_SERIAL TRUE +#endif + +/** + * @brief Enables the SERIAL over USB subsystem. + */ +#if !defined(HAL_USE_SERIAL_USB) || defined(__DOXYGEN__) +#define HAL_USE_SERIAL_USB FALSE +#endif + +/** + * @brief Enables the SPI subsystem. + */ +#if !defined(HAL_USE_SPI) || defined(__DOXYGEN__) +#define HAL_USE_SPI FALSE +#endif + +/** + * @brief Enables the UART subsystem. + */ +#if !defined(HAL_USE_UART) || defined(__DOXYGEN__) +#define HAL_USE_UART FALSE +#endif + +/** + * @brief Enables the USB subsystem. + */ +#if !defined(HAL_USE_USB) || defined(__DOXYGEN__) +#define HAL_USE_USB FALSE +#endif + +/*===========================================================================*/ +/* ADC driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Enables synchronous APIs. + * @note Disabling this option saves both code and data space. + */ +#if !defined(ADC_USE_WAIT) || defined(__DOXYGEN__) +#define ADC_USE_WAIT TRUE +#endif + +/** + * @brief Enables the @p adcAcquireBus() and @p adcReleaseBus() APIs. + * @note Disabling this option saves both code and data space. + */ +#if !defined(ADC_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__) +#define ADC_USE_MUTUAL_EXCLUSION TRUE +#endif + +/*===========================================================================*/ +/* CAN driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Sleep mode related APIs inclusion switch. + */ +#if !defined(CAN_USE_SLEEP_MODE) || defined(__DOXYGEN__) +#define CAN_USE_SLEEP_MODE TRUE +#endif + +/*===========================================================================*/ +/* I2C driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Enables the mutual exclusion APIs on the I2C bus. + */ +#if !defined(I2C_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__) +#define I2C_USE_MUTUAL_EXCLUSION TRUE +#endif + +/*===========================================================================*/ +/* MAC driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Enables an event sources for incoming packets. + */ +#if !defined(MAC_USE_ZERO_COPY) || defined(__DOXYGEN__) +#define MAC_USE_ZERO_COPY FALSE +#endif + +/** + * @brief Enables an event sources for incoming packets. + */ +#if !defined(MAC_USE_EVENTS) || defined(__DOXYGEN__) +#define MAC_USE_EVENTS TRUE +#endif + +/*===========================================================================*/ +/* MMC_SPI driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Delays insertions. + * @details If enabled this options inserts delays into the MMC waiting + * routines releasing some extra CPU time for the threads with + * lower priority, this may slow down the driver a bit however. + * This option is recommended also if the SPI driver does not + * use a DMA channel and heavily loads the CPU. + */ +#if !defined(MMC_NICE_WAITING) || defined(__DOXYGEN__) +#define MMC_NICE_WAITING TRUE +#endif + +/*===========================================================================*/ +/* SDC driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Number of initialization attempts before rejecting the card. + * @note Attempts are performed at 10mS intervals. + */ +#if !defined(SDC_INIT_RETRY) || defined(__DOXYGEN__) +#define SDC_INIT_RETRY 100 +#endif + +/** + * @brief Include support for MMC cards. + * @note MMC support is not yet implemented so this option must be kept + * at @p FALSE. + */ +#if !defined(SDC_MMC_SUPPORT) || defined(__DOXYGEN__) +#define SDC_MMC_SUPPORT FALSE +#endif + +/** + * @brief Delays insertions. + * @details If enabled this options inserts delays into the MMC waiting + * routines releasing some extra CPU time for the threads with + * lower priority, this may slow down the driver a bit however. + */ +#if !defined(SDC_NICE_WAITING) || defined(__DOXYGEN__) +#define SDC_NICE_WAITING TRUE +#endif + +/*===========================================================================*/ +/* SERIAL driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Default bit rate. + * @details Configuration parameter, this is the baud rate selected for the + * default configuration. + */ +#if !defined(SERIAL_DEFAULT_BITRATE) || defined(__DOXYGEN__) +#define SERIAL_DEFAULT_BITRATE 38400 +#endif + +/** + * @brief Serial buffers size. + * @details Configuration parameter, you can change the depth of the queue + * buffers depending on the requirements of your application. + * @note The default is 64 bytes for both the transmission and receive + * buffers. + */ +#if !defined(SERIAL_BUFFERS_SIZE) || defined(__DOXYGEN__) +#define SERIAL_BUFFERS_SIZE 16 +#endif + +/*===========================================================================*/ +/* SPI driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Enables synchronous APIs. + * @note Disabling this option saves both code and data space. + */ +#if !defined(SPI_USE_WAIT) || defined(__DOXYGEN__) +#define SPI_USE_WAIT TRUE +#endif + +/** + * @brief Enables the @p spiAcquireBus() and @p spiReleaseBus() APIs. + * @note Disabling this option saves both code and data space. + */ +#if !defined(SPI_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__) +#define SPI_USE_MUTUAL_EXCLUSION TRUE +#endif + +#endif /* _HALCONF_H_ */ + +/** @} */ diff --git a/sw/airborne/boards/lia/chibios/mcuconf.h b/sw/airborne/boards/lia/chibios/mcuconf.h new file mode 100644 index 00000000000..ecd8c9f09eb --- /dev/null +++ b/sw/airborne/boards/lia/chibios/mcuconf.h @@ -0,0 +1,213 @@ +/* + ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio + + modified by: AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + Utah State University, http://aggieair.usu.edu/ + + Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + Calvin Coopmans (c.r.coopmans@ieee.org) + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +/* + * STM32F107 drivers configuration. + * The following settings override the default settings present in + * the various device driver implementation headers. + * Note that the settings for each driver only have effect if the whole + * driver is enabled in halconf.h. + * + * IRQ priorities: + * 15...0 Lowest...Highest. + * + * DMA priorities: + * 0...3 Lowest...Highest. + */ + +#define STM32F107_MCUCONF + +/* + * HAL driver system settings. + */ +#define STM32_NO_INIT FALSE +#define STM32_HSI_ENABLED TRUE//was true +#define STM32_LSI_ENABLED FALSE +#define STM32_HSE_ENABLED TRUE +#define STM32_LSE_ENABLED FALSE +#define STM32_SW STM32_SW_PLL +#define STM32_PLLSRC STM32_PLLSRC_PREDIV1 +#define STM32_PREDIV1SRC STM32_PREDIV1SRC_HSE +#define STM32_PREDIV1_VALUE 1 +#define STM32_PLLMUL_VALUE 6 +#define STM32_PREDIV2_VALUE 3//we are not using PLL2/3 +#define STM32_PLL2MUL_VALUE 10 +#define STM32_PLL3MUL_VALUE 12 +#define STM32_HPRE STM32_HPRE_DIV1 +#define STM32_PPRE1 STM32_PPRE1_DIV2 +#define STM32_PPRE2 STM32_PPRE2_DIV1 +#define STM32_ADCPRE STM32_ADCPRE_DIV6 +#define STM32_OTG_CLOCK_REQUIRED TRUE +#define STM32_OTGFSPRE STM32_OTGFSPRE_DIV3 +#define STM32_I2S_CLOCK_REQUIRED FALSE +#define STM32_MCOSEL STM32_MCOSEL_NOCLOCK +#define STM32_RTCSEL STM32_RTCSEL_NOCLOCK +#define STM32_PVD_ENABLE FALSE +#define STM32_PLS STM32_PLS_LEV0 + +/* + * ADC driver system settings. + */ +#define STM32_ADC_USE_ADC1 FALSE +#define STM32_ADC_ADC1_DMA_PRIORITY 2 +#define STM32_ADC_ADC1_IRQ_PRIORITY 6 + +/* + * CAN driver system settings. + */ +#define STM32_CAN_USE_CAN1 FALSE +#define STM32_CAN_USE_CAN2 FALSE +#define STM32_CAN_CAN1_IRQ_PRIORITY 11 +#define STM32_CAN_CAN2_IRQ_PRIORITY 11 + +/* + * EXT driver system settings. + */ +#define STM32_EXT_EXTI0_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI1_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI2_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI3_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI4_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI5_9_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI10_15_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI16_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI17_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI18_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI19_IRQ_PRIORITY 6 + +/* + * GPT driver system settings. + */ +#define STM32_GPT_USE_TIM1 FALSE +#define STM32_GPT_USE_TIM2 FALSE +#define STM32_GPT_USE_TIM3 FALSE +#define STM32_GPT_USE_TIM4 FALSE +#define STM32_GPT_USE_TIM5 FALSE +#define STM32_GPT_USE_TIM8 FALSE +#define STM32_GPT_TIM1_IRQ_PRIORITY 7 +#define STM32_GPT_TIM2_IRQ_PRIORITY 7 +#define STM32_GPT_TIM3_IRQ_PRIORITY 7 +#define STM32_GPT_TIM4_IRQ_PRIORITY 7 +#define STM32_GPT_TIM5_IRQ_PRIORITY 7 +#define STM32_GPT_TIM8_IRQ_PRIORITY 7 + +/* + * I2C driver system settings. + */ +#define STM32_I2C_USE_I2C1 FALSE +#define STM32_I2C_USE_I2C2 FALSE +#define STM32_I2C_I2C1_IRQ_PRIORITY 5 +#define STM32_I2C_I2C2_IRQ_PRIORITY 5 +#define STM32_I2C_I2C1_DMA_PRIORITY 3 +#define STM32_I2C_I2C2_DMA_PRIORITY 3 +#define STM32_I2C_I2C1_DMA_ERROR_HOOK() chSysHalt() +#define STM32_I2C_I2C2_DMA_ERROR_HOOK() chSysHalt() + +/* + * ICU driver system settings. + */ +#define STM32_ICU_USE_TIM1 FALSE +#define STM32_ICU_USE_TIM2 FALSE +#define STM32_ICU_USE_TIM3 FALSE +#define STM32_ICU_USE_TIM4 FALSE +#define STM32_ICU_USE_TIM5 FALSE +#define STM32_ICU_USE_TIM8 FALSE +#define STM32_ICU_TIM1_IRQ_PRIORITY 7 +#define STM32_ICU_TIM2_IRQ_PRIORITY 7 +#define STM32_ICU_TIM3_IRQ_PRIORITY 7 +#define STM32_ICU_TIM4_IRQ_PRIORITY 7 +#define STM32_ICU_TIM5_IRQ_PRIORITY 7 +#define STM32_ICU_TIM8_IRQ_PRIORITY 7 + +/* + * PWM driver system settings. + */ +#define STM32_PWM_USE_ADVANCED FALSE +#define STM32_PWM_USE_TIM1 FALSE +#define STM32_PWM_USE_TIM2 FALSE +#define STM32_PWM_USE_TIM3 FALSE +#define STM32_PWM_USE_TIM4 FALSE +#define STM32_PWM_USE_TIM5 FALSE +#define STM32_PWM_USE_TIM8 FALSE +#define STM32_PWM_TIM1_IRQ_PRIORITY 7 +#define STM32_PWM_TIM2_IRQ_PRIORITY 7 +#define STM32_PWM_TIM3_IRQ_PRIORITY 7 +#define STM32_PWM_TIM4_IRQ_PRIORITY 7 +#define STM32_PWM_TIM5_IRQ_PRIORITY 7 +#define STM32_PWM_TIM8_IRQ_PRIORITY 7 + +/* + * RTC driver system settings. + */ +#define STM32_RTC_IRQ_PRIORITY 15 + +/* + * SERIAL driver system settings. + */ +#define STM32_SERIAL_USE_USART1 TRUE +#define STM32_SERIAL_USE_USART2 TRUE +#define STM32_SERIAL_USE_USART3 TRUE +#define STM32_SERIAL_USE_UART4 FALSE +#define STM32_SERIAL_USE_UART5 TRUE +#define STM32_SERIAL_USART1_PRIORITY 12 +#define STM32_SERIAL_USART2_PRIORITY 12 +#define STM32_SERIAL_USART3_PRIORITY 12 +#define STM32_SERIAL_UART4_PRIORITY 12 +#define STM32_SERIAL_UART5_PRIORITY 12 + +/* + * SPI driver system settings. + */ +#define STM32_SPI_USE_SPI1 FALSE +#define STM32_SPI_USE_SPI2 FALSE +#define STM32_SPI_USE_SPI3 FALSE +#define STM32_SPI_SPI1_DMA_PRIORITY 1 +#define STM32_SPI_SPI2_DMA_PRIORITY 1 +#define STM32_SPI_SPI3_DMA_PRIORITY 1 +#define STM32_SPI_SPI1_IRQ_PRIORITY 10 +#define STM32_SPI_SPI2_IRQ_PRIORITY 10 +#define STM32_SPI_SPI3_IRQ_PRIORITY 10 +#define STM32_SPI_DMA_ERROR_HOOK(spip) chSysHalt() + +/* + * UART driver system settings. + */ +#define STM32_UART_USE_USART1 FALSE +#define STM32_UART_USE_USART2 FALSE +#define STM32_UART_USE_USART3 FALSE +#define STM32_UART_USART1_IRQ_PRIORITY 12 +#define STM32_UART_USART2_IRQ_PRIORITY 12 +#define STM32_UART_USART3_IRQ_PRIORITY 12 +#define STM32_UART_USART1_DMA_PRIORITY 0 +#define STM32_UART_USART2_DMA_PRIORITY 0 +#define STM32_UART_USART3_DMA_PRIORITY 0 +#define STM32_UART_DMA_ERROR_HOOK(uartp) chSysHalt() + +/* + * USB driver system settings. + */ +#define STM32_USB_USE_OTG1 FALSE +#define STM32_USB_OTG1_IRQ_PRIORITY 14 +#define STM32_USB_OTG1_RX_FIFO_SIZE 512 +#define STM32_USB_OTG_THREAD_PRIO LOWPRIO +#define STM32_USB_OTG_THREAD_STACK_SIZE 128 +#define STM32_USB_OTGFIFO_FILL_BASEPRI 0 diff --git a/sw/airborne/firmwares/rotorcraft/main_chibios.c b/sw/airborne/firmwares/rotorcraft/main_chibios.c new file mode 100644 index 00000000000..4e4cad6fbf0 --- /dev/null +++ b/sw/airborne/firmwares/rotorcraft/main_chibios.c @@ -0,0 +1,290 @@ +/* + * Copyright (C) 2013 AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications + * Utah State University, http://aggieair.usu.edu/ + * + * Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) + * Calvin Coopmans (c.r.coopmans@ieee.org) + * + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ +/** + * @file main_chibios.c + * + * @brief Main file for ChibiOS/RT Paparazzi + * @details Includes both Paparazzi and ChibiOs files + * Threads are static, the memory allocation is + * just approximate at this point. Eventually + * most of the variables should be static. + * + * @author {Michal Podhradsky, Calvin Coopmans} + */ + +/** + * Chibios includes + */ +#include "ch.h" +#include "hal.h" + +/** + * Paparazzi includes + */ +#include "led.h" +#include "mcu.h" + +#include "subsystems/datalink/downlink.h" +#include "firmwares/rotorcraft/telemetry.h" +#include "subsystems/datalink/datalink.h" +#include "subsystems/settings.h" +#include "subsystems/datalink/xbee.h" +#if DATALINK == UDP +#include "subsystems/datalink/udp.h" +#endif + +#include "subsystems/commands.h" +#include "subsystems/actuators.h" +#if USE_MOTOR_MIXING +#include "subsystems/actuators/motor_mixing.h" +#endif + +#include "subsystems/imu.h" +#include "subsystems/gps.h" +#include "subsystems/air_data.h" + +#if USE_BARO_BOARD +#include "subsystems/sensors/baro.h" +#endif + +#include "subsystems/electrical.h" + +#include "firmwares/rotorcraft/autopilot.h" + +#include "firmwares/rotorcraft/stabilization.h" +#include "firmwares/rotorcraft/guidance.h" + +#include "subsystems/ahrs.h" +#include "subsystems/ins.h" + +#include "state.h" + +#include "firmwares/rotorcraft/main.h" + +#ifdef SITL +#include "nps_autopilot.h" +#endif + +#include "generated/modules.h" +#include "subsystems/abi.h" + + +/* + * Thread definitions + */ +static __attribute__((noreturn)) msg_t thd_heartbeat(void *arg); + +#ifdef DOWNLINK +static __attribute__((noreturn)) msg_t thd_telemetry_tx(void *arg); +static __attribute__((noreturn)) msg_t thd_telemetry_rx(void *arg); +#endif + +#if USE_GPS +static __attribute__((noreturn)) msg_t thd_gps_rx(void *arg); +#endif + + +/* if PRINT_CONFIG is defined, print some config options */ +PRINT_CONFIG_VAR(PERIODIC_FREQUENCY) + +/* TELEMETRY_FREQUENCY is defined in generated/periodic_telemetry.h + * defaults to 60Hz or set by TELEMETRY_FREQUENCY configure option in airframe file + */ +PRINT_CONFIG_VAR(TELEMETRY_FREQUENCY) + +/* MODULES_FREQUENCY is defined in generated/modules.h + * according to main_freq parameter set for modules in airframe file + */ +PRINT_CONFIG_VAR(MODULES_FREQUENCY) + +#ifndef BARO_PERIODIC_FREQUENCY +#define BARO_PERIODIC_FREQUENCY 50 +#endif +PRINT_CONFIG_VAR(BARO_PERIODIC_FREQUENCY) + +/* + * HeartBeat & System Info + */ +static WORKING_AREA(wa_thd_heartbeat, 128); +static __attribute__((noreturn)) msg_t thd_heartbeat(void *arg) +{ + chRegSetThreadName("pprz heartbeat"); + (void) arg; + systime_t time = chTimeNow(); // Current time + while (TRUE) { + time += MS2ST(1000); // Next deadline, sleep for one sec. + LED_TOGGLE(SYS_TIME_LED); + core_free_memory = chCoreStatus(); + heap_fragments = chHeapStatus(NULL, &heap_free_total); + Thread *tp; + thread_counter = 0; + tp = chRegFirstThread(); + do { + thread_counter++; + tp = chRegNextThread(tp); + } while (tp != NULL); + cpu_frequency = idle_counter/cpu_counter; + idle_counter = 0; + cpu_counter = 0; + chThdSleepUntil(time); + } +} + + +#if USE_GPS +/* + * GPS, just RX thread for now + * Replaces GpsEvent() + * @note _gps_callback() has to be implemented, memory can be probably smaller + */ +static WORKING_AREA(wa_thd_gps_rx, 1024); +static __attribute__((noreturn)) msg_t thd_gps_rx(void *arg) +{ + chRegSetThreadName("pprz_gps_rx"); + (void) arg; + // Only internals of the thread are defined for now + //when it was properly defined in gps file, there were problems with dependencies + GpsThread(); +} +#endif + + +#ifdef DOWNLINK +/* + * Telemetry TX + * Replaces telemetryPeriodic() + */ +static WORKING_AREA(wa_thd_telemetry_tx, 1024); +static __attribute__((noreturn)) msg_t thd_telemetry_tx(void *arg) +{ + chRegSetThreadName("pprz_telemetry_tx"); + (void) arg; + systime_t time = chTimeNow(); + while (TRUE) { + //Due to integer rounding, the actual frequency is 62.5Hz + time += MS2ST(1000/TELEMETRY_FREQUENCY); +#ifdef BARO_LED + LED_TOGGLE(BARO_LED);//DEBUG +#endif + PeriodicSendMain(DefaultChannel,DefaultDevice); + chThdSleepUntil(time); + } +} + +/* + * Telemetry RX + * Replaces DatalinkEvent() + * @note: assumes PprziDwonlink for now + * @todo General definition for different links + */ +static WORKING_AREA(wa_thd_telemetry_rx, 1024); +static __attribute__((noreturn)) msg_t thd_telemetry_rx(void *arg) +{ + chRegSetThreadName("pprz_telemetry_rx"); + (void) arg; + EventListener elTelemetryRx; + flagsmask_t flags; + chEvtRegisterMask((EventSource *)chnGetEventSource(&SD2), &elTelemetryRx, EVENT_MASK(1)); + + while (TRUE) + { + chEvtWaitOneTimeout(EVENT_MASK(1), MS2ST(10)); + chSysLock(); + flags = chEvtGetAndClearFlags(&elTelemetryRx); + chSysUnlock(); + + if (flags & CHN_INPUT_AVAILABLE) + { + msg_t charbuf; + do + { + charbuf = chnGetTimeout(&SD2, TIME_IMMEDIATE); + if ( charbuf != Q_TIMEOUT ) + { + parse_pprz(&pprz_tp, charbuf); + } + } + while (charbuf != Q_TIMEOUT); + } + if (pprz_tp.trans.msg_received) { + pprz_parse_payload(&(pprz_tp)); \ + pprz_tp.trans.msg_received = FALSE; \ + dl_parse_msg(); + dl_msg_available = FALSE; + LED_TOGGLE(RADIO_CONTROL_LED);//DEBUG + } + } +} +#endif + +/* + * Main loop + * Initializes system (both chibios and paparazzi), then goes to sleep. + * Eventually Main thread will be turned into Idle thread. + */ +int main(void) { + /* + * System initializations. + * - HAL initialization, this also initializes the configured device drivers + * and performs the board-specific initializations. + * - Kernel initialization, the main() function becomes a thread and the + * RTOS is active. + */ + halInit(); + chSysInit(); + + /* + * Paparazzi initialization + */ + mcu_init(); + electrical_init(); +#if USE_GPS + gps_init(); +#endif + + + /* + * Thread initialization + */ + chThdCreateStatic(wa_thd_heartbeat, sizeof(wa_thd_heartbeat), IDLEPRIO, thd_heartbeat, NULL); +#ifdef DOWNLINK + chThdCreateStatic(wa_thd_telemetry_tx, sizeof(wa_thd_telemetry_tx),LOWPRIO, thd_telemetry_tx, NULL); + chThdCreateStatic(wa_thd_telemetry_rx, sizeof(wa_thd_telemetry_rx),NORMALPRIO, thd_telemetry_rx, NULL); +#endif +#if USE_GPS + chThdCreateStatic(wa_thd_gps_rx, sizeof(wa_thd_gps_rx),NORMALPRIO, thd_gps_rx, NULL); +#endif + + + /* + * Normal main() thread activity, in this demo it does nothing except + * sleeping in a loop. Eventually we want to modify main to an idle thread. + */ + while (TRUE) { + chThdSleepMilliseconds(500); + } + return 1; +} diff --git a/sw/airborne/firmwares/rotorcraft/telemetry.h b/sw/airborne/firmwares/rotorcraft/telemetry.h index 33db5f41cd6..c976a716566 100644 --- a/sw/airborne/firmwares/rotorcraft/telemetry.h +++ b/sw/airborne/firmwares/rotorcraft/telemetry.h @@ -49,7 +49,9 @@ #include "subsystems/ins.h" #include "subsystems/ahrs.h" // I2C Error counters +#ifndef USE_CHIBIOS_RTOS #include "mcu_periph/i2c.h" +#endif #define PERIODIC_SEND_ALIVE(_trans, _dev) DOWNLINK_SEND_ALIVE(_trans, _dev, 16, MD5SUM) @@ -1106,4 +1108,19 @@ #define PERIODIC_SEND_GX3_INFO(_trans, _dev) {} #endif +#ifdef USE_CHIBIOS_RTOS +#include "mcu_periph/sys_time_arch.h" +#define PERIODIC_SEND_CHIBIOS_INFO(_trans, _dev) DOWNLINK_SEND_CHIBIOS_INFO(_trans, _dev, \ + &heap_fragments, \ + &heap_free_total, \ + &core_free_memory,\ + &(chTimeNow()), \ + &thread_counter, \ + &cpu_counter, \ + &idle_counter, \ + &cpu_frequency ) +#else +#define PERIODIC_SEND_CHIBIOS_INFO(_trans, _dev) {} +#endif + #endif /* TELEMETRY_H */ diff --git a/sw/airborne/mcu_periph/uart_pprzi.c b/sw/airborne/mcu_periph/uart_pprzi.c new file mode 100644 index 00000000000..34f325c0914 --- /dev/null +++ b/sw/airborne/mcu_periph/uart_pprzi.c @@ -0,0 +1,81 @@ +/* + * Copyright (C) 2010 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + + /** + * @brief arch independent UART (Universal Asynchronous Receiver/Transmitter) API + * @note Had to be renamed, since chibios is using the same filename for its own + * UART drivers. Modified by Aggiear (http://aggieair.usu.edu/), 2013 + * + */ +#include "mcu_periph/uart.h" + +#ifdef USE_UART0 +struct uart_periph uart0; +#endif + +#ifdef USE_UART1 +struct uart_periph uart1; +#endif + +#ifdef USE_UART2 +struct uart_periph uart2; +#endif + +#ifdef USE_UART3 +struct uart_periph uart3; +#endif + +#ifdef USE_UART4 +struct uart_periph uart4; +#endif + +#ifdef USE_UART5 +struct uart_periph uart5; +#endif + +#ifdef USE_UART6 +struct uart_periph uart6; +#endif + +void uart_periph_init(struct uart_periph* p) { + p->rx_insert_idx = 0; + p->rx_extract_idx = 0; + p->tx_insert_idx = 0; + p->tx_extract_idx = 0; + p->tx_running = FALSE; + p->ore = 0; + p->ne_err = 0; + p->fe_err = 0; +} + +bool_t uart_check_free_space(struct uart_periph* p, uint8_t len) { + int16_t space = p->tx_extract_idx - p->tx_insert_idx; + if (space <= 0) + space += UART_TX_BUFFER_SIZE; + return (uint16_t)(space - 1) >= len; +} + +uint8_t uart_getch(struct uart_periph* p) { + uint8_t ret = p->rx_buf[p->rx_extract_idx]; + p->rx_extract_idx = (p->rx_extract_idx + 1) % UART_RX_BUFFER_SIZE; + return ret; +} diff --git a/sw/airborne/subsystems/gps/gps_ubx.c b/sw/airborne/subsystems/gps/gps_ubx.c index 260ed719837..cb29094d2b8 100644 --- a/sw/airborne/subsystems/gps/gps_ubx.c +++ b/sw/airborne/subsystems/gps/gps_ubx.c @@ -274,7 +274,9 @@ void gps_ubx_parse( uint8_t c ) { void ubxsend_cfg_rst(uint16_t bbr , uint8_t reset_mode) { #ifdef GPS_LINK +#ifndef USE_UART5 UbxSend_CFG_RST(bbr, reset_mode, 0x00); +#endif #endif /* else less harmful for HITL */ } diff --git a/sw/airborne/subsystems/gps/gps_ubx.h b/sw/airborne/subsystems/gps/gps_ubx.h index dab9de81a55..f37106155b8 100644 --- a/sw/airborne/subsystems/gps/gps_ubx.h +++ b/sw/airborne/subsystems/gps/gps_ubx.h @@ -79,6 +79,7 @@ extern struct GpsUbx gps_ubx; * All position/speed messages are sent in one shot and VELNED is the last one on fixedwing * For rotorcraft, only SOL message is needed for pos/speed data */ +#ifndef USE_CHIBIOS_RTOS #define GpsEvent(_sol_available_callback) { \ if (GpsBuffer()) { \ ReadGpsBuffer(); \ @@ -104,7 +105,47 @@ extern struct GpsUbx gps_ubx; while (GpsLink(ChAvailable())&&!gps_ubx.msg_available) \ gps_ubx_parse(GpsLink(Getch())); \ } - +#else +#define GpsThread() { \ + EventListener elGPSdata; \ + flagsmask_t flags; \ + chEvtRegisterMask((EventSource *)chnGetEventSource(&SD5), &elGPSdata, EVENT_MASK(1)); \ + while (TRUE) \ + { \ + chEvtWaitOneTimeout(EVENT_MASK(1), MS2ST(100));\ + chSysLock();\ + flags = chEvtGetAndClearFlags(&elGPSdata);\ + chSysUnlock();\ + if (flags & CHN_INPUT_AVAILABLE)\ + {\ + msg_t charbuf;\ + do \ + {\ + charbuf = chnGetTimeout(&SD5, TIME_IMMEDIATE);\ + if ( charbuf != Q_TIMEOUT )\ + {\ + gps_ubx_parse(charbuf);\ + }\ + }\ + while (charbuf != Q_TIMEOUT);\ + }\ + if (gps_ubx.msg_available) { \ + gps_ubx_read_message(); \ + gps_ubx_ucenter_event(); \ + if (gps_ubx.msg_class == UBX_NAV_ID && \ + (gps_ubx.msg_id == UBX_NAV_VELNED_ID || \ + (gps_ubx.msg_id == UBX_NAV_SOL_ID && \ + gps_ubx.have_velned == 0))) { \ + if (gps.fix == GPS_FIX_3D) { \ + gps.last_fix_ticks = sys_time.nb_sec_rem; \ + gps.last_fix_time = sys_time.nb_sec; \ + } \ + }\ + gps_ubx.msg_available = FALSE;\ + }\ + }\ +} +#endif extern void gps_ubx_read_message(void); extern void gps_ubx_parse(uint8_t c); diff --git a/sw/include/std.h b/sw/include/std.h index a8b86408e98..cb49ed6035f 100644 --- a/sw/include/std.h +++ b/sw/include/std.h @@ -70,7 +70,11 @@ #endif /* Boolean values */ +#ifndef USE_CHIBIOS_RTOS //Hack for compiling two boolean typedefs (see chtypes.h) typedef uint8_t bool_t; +#else +#include "chtypes.h" +#endif /* Unit (void) values */ typedef uint8_t unit_t; diff --git a/sw/tools/dfu/stm32_mem.py b/sw/tools/dfu/stm32_mem.py old mode 100644 new mode 100755